rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
moveit_planning_scene.h
Go to the documentation of this file.
1 #ifndef _RAPID_MOVEIT_PLANNING_SCENE_H_
2 #define _RAPID_MOVEIT_PLANNING_SCENE_H_
3 
4 #include <string>
5 
6 #include "geometry_msgs/PoseStamped.h"
7 #include "geometry_msgs/Vector3.h"
8 #include "ros/ros.h"
9 
10 namespace rapid {
22  public:
25 
29  explicit MoveItPlanningScene(const std::string& topic);
30 
40  void AddBoxObstacle(const std::string& name,
41  const geometry_msgs::PoseStamped& pose_stamped,
42  const geometry_msgs::Vector3& dims);
43 
47  void RemoveObstacle(const std::string& name);
48 
49  private:
50  void Init();
51 
52  std::string topic_;
53  ros::NodeHandle nh_;
54  ros::Publisher pub_;
55 };
56 } // namespace rapid
57 
58 #endif // _RAPID_MOVEIT_PLANNING_SCENE_H_
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.
MoveItPlanningScene()
Default constructor, planning scene topic is "/planning_scene".
Simple interface to the MoveIt planning scene monitor.
void RemoveObstacle(const std::string &name)
Removes an obstacle from the planning scene.