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
00049 #include <arm_navigation_msgs/Shape.h>
00050
00051 #include <tabletop_object_detector/Table.h>
00052 #include <tabletop_object_detector/TabletopDetectionResult.h>
00053
00054 #include <object_manipulation_msgs/GraspableObject.h>
00055 #include <object_manipulation_msgs/ClusterBoundingBox.h>
00056
00057 namespace tabletop_collision_map_processing {
00058
00060 class CollisionMapException : public std::runtime_error
00061 {
00062 public:
00063 CollisionMapException(const std::string error) : std::runtime_error("collision map: "+error) {};
00064 };
00065
00067 class CollisionMapInterface
00068 {
00069 private:
00071 ros::NodeHandle root_nh_;
00072
00074 ros::NodeHandle priv_nh_;
00075
00077 bool connections_established_;
00078
00080 ros::Publisher collision_object_pub_;
00081
00083 ros::Publisher attached_object_pub_;
00084
00086 ros::ServiceClient cluster_bounding_box_client_;
00087 ros::ServiceClient cluster_bounding_box2_client_;
00088 ros::ServiceClient cluster_bounding_box_3d_client_;
00089 ros::ServiceClient cluster_bounding_box2_3d_client_;
00090
00092 ros::ServiceClient get_model_mesh_srv_;
00093
00095 int collision_object_current_id_;
00096
00098 bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00099 arm_navigation_msgs::Shape& mesh);
00100
00102 std::string getNextObjectName();
00103
00105 bool connectionsPresent();
00106
00108 void connectServices();
00109
00111 int point_skip_num_;
00112
00114 int collision_box_size_;
00115
00117 double table_thickness_;
00118
00119 public:
00121 CollisionMapInterface();
00122
00124
00126 bool connectionsEstablished(ros::Duration timeout);
00127
00129 void processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00130 std::string table_collision_name);
00131
00133 void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00134 std::string &collision_name);
00135
00137 void processCollisionGeometryForObjectAsBoundingBox
00138 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00139 std::string &collision_name);
00140
00142 void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00143 std::string &collision_name, float collision_size = -1.0);
00144
00146 void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00147 std::string &collision_name);
00148
00150 void removeCollisionModel(std::string collision_name);
00151
00153 void resetCollisionModels();
00154
00156 void resetAttachedModels();
00157
00158 void resetCollisionId(int id = 0){collision_object_current_id_ = id;}
00159
00161 void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00162 geometry_msgs::PoseStamped &pose_stamped,
00163 geometry_msgs::Vector3 &dimensions);
00164
00166 void getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster,
00167 geometry_msgs::PoseStamped &pose_stamped,
00168 geometry_msgs::Vector3 &dimensions);
00169
00171 void getClusterBoundingBox3D(const sensor_msgs::PointCloud &cluster,
00172 geometry_msgs::PoseStamped &pose_stamped,
00173 geometry_msgs::Vector3 &dimensions);
00174
00176 void getClusterBoundingBox3D(const sensor_msgs::PointCloud2 &cluster,
00177 geometry_msgs::PoseStamped &pose_stamped,
00178 geometry_msgs::Vector3 &dimensions);
00179
00181 bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00182 geometry_msgs::PoseStamped &pose_stamped,
00183 geometry_msgs::Vector3 &dimensions);
00184 };
00185
00186 }
00187
00188 #endif