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_SEMANTIC_WORLD_
00038 #define MOVEIT_SEMANTIC_WORLD_
00039
00040 #include <ros/ros.h>
00041 #include <moveit/macros/class_forward.h>
00042 #include <moveit/planning_scene/planning_scene.h>
00043 #include <object_recognition_msgs/TableArray.h>
00044 #include <moveit_msgs/CollisionObject.h>
00045 #include <geometric_shapes/shapes.h>
00046
00047 #include <boost/thread/mutex.hpp>
00048
00049 namespace moveit
00050 {
00051 namespace semantic_world
00052 {
00053 MOVEIT_CLASS_FORWARD(SemanticWorld);
00054
00058 class SemanticWorld
00059 {
00060 public:
00062 typedef boost::function<void()> TableCallbackFn;
00063
00068 SemanticWorld(const planning_scene::PlanningSceneConstPtr& planning_scene);
00069
00073 object_recognition_msgs::TableArray getTablesInROI(double minx, double miny, double minz, double maxx, double maxy,
00074 double maxz) const;
00075
00079 std::vector<std::string> getTableNamesInROI(double minx, double miny, double minz, double maxx, double maxy,
00080 double maxz) const;
00081
00087 std::vector<geometry_msgs::PoseStamped> generatePlacePoses(const std::string& table_name,
00088 const shapes::ShapeConstPtr& object_shape,
00089 const geometry_msgs::Quaternion& object_orientation,
00090 double resolution, double delta_height = 0.01,
00091 unsigned int num_heights = 2) const;
00092
00098 std::vector<geometry_msgs::PoseStamped> generatePlacePoses(const object_recognition_msgs::Table& table,
00099 const shapes::ShapeConstPtr& object_shape,
00100 const geometry_msgs::Quaternion& object_orientation,
00101 double resolution, double delta_height = 0.01,
00102 unsigned int num_heights = 2) const;
00110 std::vector<geometry_msgs::PoseStamped> generatePlacePoses(const object_recognition_msgs::Table& table,
00111 double resolution, double height_above_table,
00112 double delta_height = 0.01, unsigned int num_heights = 2,
00113 double min_distance_from_edge = 0.10) const;
00114
00115 void clear();
00116
00117 bool addTablesToCollisionWorld();
00118
00119 visualization_msgs::MarkerArray getPlaceLocationsMarker(const std::vector<geometry_msgs::PoseStamped>& poses) const;
00120
00121 void addTableCallback(const TableCallbackFn& table_callback)
00122 {
00123 table_callback_ = table_callback;
00124 }
00125
00126 std::string findObjectTable(const geometry_msgs::Pose& pose, double min_distance_from_edge = 0.0,
00127 double min_vertical_offset = 0.0) const;
00128
00129 bool isInsideTableContour(const geometry_msgs::Pose& pose, const object_recognition_msgs::Table& table,
00130 double min_distance_from_edge = 0.0, double min_vertical_offset = 0.0) const;
00131
00132 private:
00133 shapes::Mesh* createSolidMeshFromPlanarPolygon(const shapes::Mesh& polygon, double thickness) const;
00134
00135 shapes::Mesh* orientPlanarPolygon(const shapes::Mesh& polygon) const;
00136
00137 void tableCallback(const object_recognition_msgs::TableArrayPtr& msg);
00138
00139 void transformTableArray(object_recognition_msgs::TableArray& table_array) const;
00140
00141 planning_scene::PlanningSceneConstPtr planning_scene_;
00142
00143 ros::NodeHandle node_handle_;
00144
00145 object_recognition_msgs::TableArray table_array_;
00146
00147 std::vector<geometry_msgs::PoseStamped> place_poses_;
00148
00149 std::map<std::string, object_recognition_msgs::Table> current_tables_in_collision_world_;
00150
00151
00152
00153 ros::Subscriber table_subscriber_;
00154
00155 ros::Publisher visualization_publisher_, collision_object_publisher_;
00156
00157 TableCallbackFn table_callback_;
00158
00159 ros::Publisher planning_scene_diff_publisher_;
00160 };
00161 }
00162 }
00163
00164 #endif