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 #ifndef _COLLISION_MAP_INTERFACE_H_
00037 #define _COLLISION_MAP_INTERFACE_H_
00038
00039 #include <stdexcept>
00040
00041 #include <ros/ros.h>
00042
00043 #include <actionlib/client/simple_action_client.h>
00044
00045 #include <collision_environment_msgs/MakeStaticCollisionMapAction.h>
00046
00047 #include <household_objects_database_msgs/DatabaseModelPose.h>
00048
00049 #include <sensor_msgs/PointCloud.h>
00050
00051 #include <geometric_shapes_msgs/Shape.h>
00052
00053 #include <tabletop_object_detector/Table.h>
00054 #include <tabletop_object_detector/TabletopDetectionResult.h>
00055
00056 #include <object_manipulation_msgs/GraspableObject.h>
00057 #include <object_manipulation_msgs/ClusterBoundingBox.h>
00058
00059 namespace tabletop_collision_map_processing {
00060
00062 class CollisionMapException : public std::runtime_error
00063 {
00064 public:
00065 CollisionMapException(const std::string error) : std::runtime_error("collision map: "+error) {};
00066 };
00067
00069 class CollisionMapInterface
00070 {
00071 private:
00073 ros::NodeHandle root_nh_;
00074
00076 ros::NodeHandle priv_nh_;
00077
00079 bool connections_established_;
00080
00082 ros::Publisher collision_object_pub_;
00083
00085 ros::Publisher attached_object_pub_;
00086
00088 ros::ServiceClient collision_map_reset_client_;
00089
00091 ros::ServiceClient cluster_bounding_box_client_;
00092
00094 ros::ServiceClient get_model_mesh_srv_;
00095
00097 std::string static_map_cloud_name_;
00098
00100 int collision_object_current_id_;
00101
00103 actionlib::SimpleActionClient<collision_environment_msgs::MakeStaticCollisionMapAction>
00104 make_static_collision_map_client_;
00105
00107 bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00108 geometric_shapes_msgs::Shape& mesh);
00109
00111 std::string getNextObjectName();
00112
00114 bool connectionsPresent();
00115
00117 void connectServices();
00118
00120 int point_skip_num_;
00121
00123 int collision_box_size_;
00124
00125 public:
00127 CollisionMapInterface();
00128
00130
00132 bool connectionsEstablished(ros::Duration timeout);
00133
00135 void processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00136 std::string table_collision_name);
00137
00139 void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00140 std::string &collision_name);
00141
00143 void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00144 std::string &collision_name, float collision_size = -1.0);
00145
00147 void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00148 std::string &collision_name);
00149
00151 void resetCollisionModels();
00152
00154 void resetAttachedModels();
00155
00157 void resetStaticMap();
00158
00160 void takeStaticMap();
00161
00163 void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00164 geometry_msgs::PoseStamped &pose_stamped,
00165 geometry_msgs::Vector3 &dimensions);
00166
00168 bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00169 geometry_msgs::PoseStamped &pose_stamped,
00170 geometry_msgs::Vector3 &dimensions);
00171 };
00172
00173 }
00174
00175 #endif