|
rapid
A ROS robotics library.
|
Simple interface to the MoveIt planning scene monitor. More...
#include <moveit_planning_scene.h>
Public Member Functions | |
| MoveItPlanningScene () | |
| Default constructor, planning scene topic is "/planning_scene". More... | |
| MoveItPlanningScene (const std::string &topic) | |
| Constructor that takes in a planning scene topic. More... | |
| void | AddBoxObstacle (const std::string &name, const geometry_msgs::PoseStamped &pose_stamped, const geometry_msgs::Vector3 &dims) |
| Adds a box-shaped obstacle to the planning scene. More... | |
| void | RemoveObstacle (const std::string &name) |
| Removes an obstacle from the planning scene. More... | |
Simple interface to the MoveIt planning scene monitor.
Example usage:
Definition at line 21 of file moveit_planning_scene.h.
| rapid::MoveItPlanningScene::MoveItPlanningScene | ( | ) |
Default constructor, planning scene topic is "/planning_scene".
|
explicit |
Constructor that takes in a planning scene topic.
| [in] | topic | The planning scene topic to publish to. |
| void rapid::MoveItPlanningScene::AddBoxObstacle | ( | const std::string & | name, |
| const geometry_msgs::PoseStamped & | pose_stamped, | ||
| const geometry_msgs::Vector3 & | dims | ||
| ) |
Adds a box-shaped obstacle to the planning scene.
Adding an obstacle with the same name as an existing obstacle will replace it.
| [in] | name | The name of the obstacle. |
| [in] | pose_stamped | The pose of the box. Origin is at the center of the box. |
| [in] | dims | The dimensions of the box. |
| void rapid::MoveItPlanningScene::RemoveObstacle | ( | const std::string & | name | ) |
Removes an obstacle from the planning scene.
| [in] | name | The name of the obstacle to remove. |