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
00090 ros::ServiceClient get_model_mesh_srv_;
00091
00093 int collision_object_current_id_;
00094
00096 bool getMeshFromDatabasePose(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00097 arm_navigation_msgs::Shape& mesh);
00098
00100 std::string getNextObjectName();
00101
00103 bool connectionsPresent();
00104
00106 void connectServices();
00107
00109 int point_skip_num_;
00110
00112 int collision_box_size_;
00113
00115 double table_thickness_;
00116
00117 public:
00119 CollisionMapInterface();
00120
00122
00124 bool connectionsEstablished(ros::Duration timeout);
00125
00127 void processCollisionGeometryForTable(const tabletop_object_detector::Table &table,
00128 std::string table_collision_name);
00129
00131 void processCollisionGeometryForObject(const household_objects_database_msgs::DatabaseModelPose &model_pose,
00132 std::string &collision_name);
00133
00135 void processCollisionGeometryForObjectAsBoundingBox
00136 (const household_objects_database_msgs::DatabaseModelPose &model_pose,
00137 std::string &collision_name);
00138
00140 void processCollisionGeometryForCluster(const sensor_msgs::PointCloud &cluster,
00141 std::string &collision_name, float collision_size = -1.0);
00142
00144 void processCollisionGeometryForBoundingBox(const object_manipulation_msgs::ClusterBoundingBox &box,
00145 std::string &collision_name);
00146
00148 void removeCollisionModel(std::string collision_name);
00149
00151 void resetCollisionModels();
00152
00154 void resetAttachedModels();
00155
00156 void resetCollisionId(int id = 0){collision_object_current_id_ = id;}
00157
00159 void getClusterBoundingBox(const sensor_msgs::PointCloud &cluster,
00160 geometry_msgs::PoseStamped &pose_stamped,
00161 geometry_msgs::Vector3 &dimensions);
00162
00164 void getClusterBoundingBox(const sensor_msgs::PointCloud2 &cluster,
00165 geometry_msgs::PoseStamped &pose_stamped,
00166 geometry_msgs::Vector3 &dimensions);
00167
00169 bool extendBoundingBoxZToTable(const tabletop_object_detector::Table &table,
00170 geometry_msgs::PoseStamped &pose_stamped,
00171 geometry_msgs::Vector3 &dimensions);
00172 };
00173
00174 }
00175
00176 #endif