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 #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 <household_objects_database_msgs/DatabaseModelPose.h>
00046
00047 #include <sensor_msgs/PointCloud.h>
00048 #include <sensor_msgs/PointCloud2.h>
00049
00050 #include <arm_navigation_msgs/Shape.h>
00051
00052 #include <tabletop_object_detector/Table.h>
00053 #include <tabletop_object_detector/TabletopDetectionResult.h>
00054
00055
00056
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 cluster_bounding_box_client_;
00089 ros::ServiceClient cluster_bounding_box2_client_;
00090 ros::ServiceClient cluster_bounding_box_3d_client_;
00091 ros::ServiceClient cluster_bounding_box2_3d_client_;
00092
00094 ros::ServiceClient get_model_mesh_srv_;
00095
00097 int collision_object_current_id_;
00098
00100 bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00101 arm_navigation_msgs::Shape& mesh);
00102
00104 std::string getNextObjectName();
00105
00107 bool connectionsPresent();
00108
00110 void connectServices();
00111
00113 int point_skip_num_;
00114
00116 int collision_box_size_;
00117
00119 double table_thickness_;
00120
00121 public:
00123 CollisionMapInterface();
00124
00126
00128 bool connectionsEstablished(ros::Duration timeout);
00129
00131 void processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00132 std::string table_collision_name);
00133
00135 void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00136 std::string &collision_name);
00137
00139 void processCollisionGeometryForObjectAsBoundingBox
00140 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00141 std::string &collision_name);
00142
00144 void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00145 std::string &collision_name, float collision_size = -1.0);
00146
00148 void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00149 std::string &collision_name);
00150
00152 void removeCollisionModel(std::string collision_name);
00153
00155 void resetCollisionModels();
00156
00158 void resetAttachedModels();
00159
00160 void resetCollisionId(int id = 0){collision_object_current_id_ = id;}
00161
00163 void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00164 geometry_msgs::PoseStamped &pose_stamped,
00165 geometry_msgs::Vector3 &dimensions);
00166
00168 void getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster,
00169 geometry_msgs::PoseStamped &pose_stamped,
00170 geometry_msgs::Vector3 &dimensions);
00171
00173 void getClusterBoundingBox3D(const sensor_msgs::PointCloud &cluster,
00174 geometry_msgs::PoseStamped &pose_stamped,
00175 geometry_msgs::Vector3 &dimensions);
00176
00178 void getClusterBoundingBox3D(const sensor_msgs::PointCloud2 &cluster,
00179 geometry_msgs::PoseStamped &pose_stamped,
00180 geometry_msgs::Vector3 &dimensions);
00181
00183 bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00184 geometry_msgs::PoseStamped &pose_stamped,
00185 geometry_msgs::Vector3 &dimensions);
00186 };
00187
00188 }
00189
00190 #endif