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/robot_state/robot_state.h>
00041 #include <moveit_msgs/CollisionObject.h>
00042 #include <moveit_msgs/AttachedCollisionObject.h>
00043
00044 namespace moveit
00045 {
00046 namespace planning_interface
00047 {
00048
00049 class PlanningSceneInterface
00050 {
00051 public:
00052 PlanningSceneInterface();
00053 ~PlanningSceneInterface();
00054
00061 std::vector<std::string> getKnownObjectNames(bool with_type = false);
00062
00065 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type, std::vector<std::string> &types);
00066
00069 std::vector<std::string> getKnownObjectNamesInROI(double minx, double miny, double minz, double maxx, double maxy, double maxz, bool with_type = false)
00070 {
00071 std::vector<std::string> empty_vector_string;
00072 return getKnownObjectNamesInROI(minx, miny, minz, maxx, maxy, maxz, with_type, empty_vector_string);
00073 };
00074
00075 std::map<std::string, geometry_msgs::Pose> getObjectPoses(const std::vector<std::string> &object_ids);
00076
00079 void addCollisionObjects(const std::vector<moveit_msgs::CollisionObject> &collision_objects) const;
00080
00082 void removeCollisionObjects(const std::vector<std::string> &object_ids) const;
00083
00086 private:
00087
00088 class PlanningSceneInterfaceImpl;
00089 PlanningSceneInterfaceImpl *impl_;
00090
00091 };
00092
00093 }
00094 }
00095
00096 #endif