Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_SCENE_INTERFACE_
00038 #define MOVEIT_PLANNING_INTERFACE_PLANNING_SCENE_INTERFACE_
00039
00040 #include <moveit/macros/class_forward.h>
00041 #include <moveit/robot_state/robot_state.h>
00042 #include <moveit_msgs/CollisionObject.h>
00043 #include <moveit_msgs/AttachedCollisionObject.h>
00044 #include <moveit_msgs/PlanningScene.h>
00045
00046 namespace moveit
00047 {
00048 namespace planning_interface
00049 {
00050 MOVEIT_CLASS_FORWARD(PlanningSceneInterface);
00051
00052 class PlanningSceneInterface
00053 {
00054 public:
00055 PlanningSceneInterface();
00056 ~PlanningSceneInterface();
00057
00065 std::vector<std::string> getKnownObjectNames(bool with_type = false);
00066
00070 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
00071 double maxz, bool with_type, std::vector<std::string>& types);
00072
00076 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
00077 double maxz, bool with_type = false)
00078 {
00079 std::vector<std::string> empty_vector_string;
00080 return getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, empty_vector_string);
00081 };
00082
00084 std::map<std::string, geometry_msgs::Pose> getObjectPoses(const std::vector<std::string>& object_ids);
00085
00088 std::map<std::string, moveit_msgs::CollisionObject>
00089 getObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
00090
00093 std::map<std::string, moveit_msgs::AttachedCollisionObject>
00094 getAttachedObjects(const std::vector<std::string>& object_ids = std::vector<std::string>());
00095
00098 bool applyCollisionObject(const moveit_msgs::CollisionObject& collision_objects);
00099
00102 bool applyCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects);
00103
00106 bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject& attached_collision_objects);
00107
00110 bool
00111 applyAttachedCollisionObjects(const std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objects);
00112
00115 bool applyPlanningScene(const moveit_msgs::PlanningScene& ps);
00116
00122 void addCollisionObjects(const std::vector<moveit_msgs::CollisionObject>& collision_objects) const;
00123
00128 void removeCollisionObjects(const std::vector<std::string>& object_ids) const;
00129
00132 private:
00133 class PlanningSceneInterfaceImpl;
00134 PlanningSceneInterfaceImpl* impl_;
00135 };
00136 }
00137 }
00138
00139 #endif