$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_object_manipulation/doc_stacks/2013-03-05_12-10-38.333207/pr2_object_manipulation/perception/tabletop_object_detector/srv/TabletopObjectRecognition.srv */ 00002 #ifndef TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPOBJECTRECOGNITION_H 00003 #define TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPOBJECTRECOGNITION_H 00004 #include <string> 00005 #include <vector> 00006 #include <map> 00007 #include <ostream> 00008 #include "ros/serialization.h" 00009 #include "ros/builtin_message_traits.h" 00010 #include "ros/message_operations.h" 00011 #include "ros/time.h" 00012 00013 #include "ros/macros.h" 00014 00015 #include "ros/assert.h" 00016 00017 #include "ros/service_traits.h" 00018 00019 #include "tabletop_object_detector/Table.h" 00020 #include "sensor_msgs/PointCloud.h" 00021 00022 00023 #include "household_objects_database_msgs/DatabaseModelPoseList.h" 00024 00025 namespace tabletop_object_detector 00026 { 00027 template <class ContainerAllocator> 00028 struct TabletopObjectRecognitionRequest_ { 00029 typedef TabletopObjectRecognitionRequest_<ContainerAllocator> Type; 00030 00031 TabletopObjectRecognitionRequest_() 00032 : table() 00033 , clusters() 00034 , num_models(0) 00035 , perform_fit_merge(false) 00036 { 00037 } 00038 00039 TabletopObjectRecognitionRequest_(const ContainerAllocator& _alloc) 00040 : table(_alloc) 00041 , clusters(_alloc) 00042 , num_models(0) 00043 , perform_fit_merge(false) 00044 { 00045 } 00046 00047 typedef ::tabletop_object_detector::Table_<ContainerAllocator> _table_type; 00048 ::tabletop_object_detector::Table_<ContainerAllocator> table; 00049 00050 typedef std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > _clusters_type; 00051 std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > clusters; 00052 00053 typedef int32_t _num_models_type; 00054 int32_t num_models; 00055 00056 typedef uint8_t _perform_fit_merge_type; 00057 uint8_t perform_fit_merge; 00058 00059 00060 ROS_DEPRECATED uint32_t get_clusters_size() const { return (uint32_t)clusters.size(); } 00061 ROS_DEPRECATED void set_clusters_size(uint32_t size) { clusters.resize((size_t)size); } 00062 ROS_DEPRECATED void get_clusters_vec(std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > & vec) const { vec = this->clusters; } 00063 ROS_DEPRECATED void set_clusters_vec(const std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > & vec) { this->clusters = vec; } 00064 private: 00065 static const char* __s_getDataType_() { return "tabletop_object_detector/TabletopObjectRecognitionRequest"; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00068 00069 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00070 00071 private: 00072 static const char* __s_getMD5Sum_() { return "197bf138763e73e721e55b16fedc33a9"; } 00073 public: 00074 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00075 00076 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00077 00078 private: 00079 static const char* __s_getServerMD5Sum_() { return "f5867bc89b17633ae48681b939f1fbf7"; } 00080 public: 00081 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00082 00083 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00084 00085 private: 00086 static const char* __s_getMessageDefinition_() { return "\n\ 00087 Table table\n\ 00088 \n\ 00089 \n\ 00090 sensor_msgs/PointCloud[] clusters\n\ 00091 \n\ 00092 \n\ 00093 int32 num_models\n\ 00094 \n\ 00095 \n\ 00096 bool perform_fit_merge\n\ 00097 \n\ 00098 \n\ 00099 ================================================================================\n\ 00100 MSG: tabletop_object_detector/Table\n\ 00101 # Informs that a planar table has been detected at a given location\n\ 00102 \n\ 00103 # The pose gives you the transform that take you to the coordinate system\n\ 00104 # of the table, with the origin somewhere in the table plane and the \n\ 00105 # z axis normal to the plane\n\ 00106 geometry_msgs/PoseStamped pose\n\ 00107 \n\ 00108 # These values give you the observed extents of the table, along x and y,\n\ 00109 # in the table's own coordinate system (above)\n\ 00110 # there is no guarantee that the origin of the table coordinate system is\n\ 00111 # inside the boundary defined by these values. \n\ 00112 float32 x_min\n\ 00113 float32 x_max\n\ 00114 float32 y_min\n\ 00115 float32 y_max\n\ 00116 \n\ 00117 # There is no guarantee that the table does NOT extend further than these \n\ 00118 # values; this is just as far as we've observed it.\n\ 00119 \n\ 00120 \n\ 00121 # Newer table definition as triangle mesh of convex hull (relative to pose)\n\ 00122 arm_navigation_msgs/Shape convex_hull\n\ 00123 \n\ 00124 ================================================================================\n\ 00125 MSG: geometry_msgs/PoseStamped\n\ 00126 # A Pose with reference coordinate frame and timestamp\n\ 00127 Header header\n\ 00128 Pose pose\n\ 00129 \n\ 00130 ================================================================================\n\ 00131 MSG: std_msgs/Header\n\ 00132 # Standard metadata for higher-level stamped data types.\n\ 00133 # This is generally used to communicate timestamped data \n\ 00134 # in a particular coordinate frame.\n\ 00135 # \n\ 00136 # sequence ID: consecutively increasing ID \n\ 00137 uint32 seq\n\ 00138 #Two-integer timestamp that is expressed as:\n\ 00139 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00140 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00141 # time-handling sugar is provided by the client library\n\ 00142 time stamp\n\ 00143 #Frame this data is associated with\n\ 00144 # 0: no frame\n\ 00145 # 1: global frame\n\ 00146 string frame_id\n\ 00147 \n\ 00148 ================================================================================\n\ 00149 MSG: geometry_msgs/Pose\n\ 00150 # A representation of pose in free space, composed of postion and orientation. \n\ 00151 Point position\n\ 00152 Quaternion orientation\n\ 00153 \n\ 00154 ================================================================================\n\ 00155 MSG: geometry_msgs/Point\n\ 00156 # This contains the position of a point in free space\n\ 00157 float64 x\n\ 00158 float64 y\n\ 00159 float64 z\n\ 00160 \n\ 00161 ================================================================================\n\ 00162 MSG: geometry_msgs/Quaternion\n\ 00163 # This represents an orientation in free space in quaternion form.\n\ 00164 \n\ 00165 float64 x\n\ 00166 float64 y\n\ 00167 float64 z\n\ 00168 float64 w\n\ 00169 \n\ 00170 ================================================================================\n\ 00171 MSG: arm_navigation_msgs/Shape\n\ 00172 byte SPHERE=0\n\ 00173 byte BOX=1\n\ 00174 byte CYLINDER=2\n\ 00175 byte MESH=3\n\ 00176 \n\ 00177 byte type\n\ 00178 \n\ 00179 \n\ 00180 #### define sphere, box, cylinder ####\n\ 00181 # the origin of each shape is considered at the shape's center\n\ 00182 \n\ 00183 # for sphere\n\ 00184 # radius := dimensions[0]\n\ 00185 \n\ 00186 # for cylinder\n\ 00187 # radius := dimensions[0]\n\ 00188 # length := dimensions[1]\n\ 00189 # the length is along the Z axis\n\ 00190 \n\ 00191 # for box\n\ 00192 # size_x := dimensions[0]\n\ 00193 # size_y := dimensions[1]\n\ 00194 # size_z := dimensions[2]\n\ 00195 float64[] dimensions\n\ 00196 \n\ 00197 \n\ 00198 #### define mesh ####\n\ 00199 \n\ 00200 # list of triangles; triangle k is defined by tre vertices located\n\ 00201 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00202 int32[] triangles\n\ 00203 geometry_msgs/Point[] vertices\n\ 00204 \n\ 00205 ================================================================================\n\ 00206 MSG: sensor_msgs/PointCloud\n\ 00207 # This message holds a collection of 3d points, plus optional additional\n\ 00208 # information about each point.\n\ 00209 \n\ 00210 # Time of sensor data acquisition, coordinate frame ID.\n\ 00211 Header header\n\ 00212 \n\ 00213 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00214 # in the frame given in the header.\n\ 00215 geometry_msgs/Point32[] points\n\ 00216 \n\ 00217 # Each channel should have the same number of elements as points array,\n\ 00218 # and the data in each channel should correspond 1:1 with each point.\n\ 00219 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00220 ChannelFloat32[] channels\n\ 00221 \n\ 00222 ================================================================================\n\ 00223 MSG: geometry_msgs/Point32\n\ 00224 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00225 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00226 # \n\ 00227 # This recommendation is to promote interoperability. \n\ 00228 #\n\ 00229 # This message is designed to take up less space when sending\n\ 00230 # lots of points at once, as in the case of a PointCloud. \n\ 00231 \n\ 00232 float32 x\n\ 00233 float32 y\n\ 00234 float32 z\n\ 00235 ================================================================================\n\ 00236 MSG: sensor_msgs/ChannelFloat32\n\ 00237 # This message is used by the PointCloud message to hold optional data\n\ 00238 # associated with each point in the cloud. The length of the values\n\ 00239 # array should be the same as the length of the points array in the\n\ 00240 # PointCloud, and each value should be associated with the corresponding\n\ 00241 # point.\n\ 00242 \n\ 00243 # Channel names in existing practice include:\n\ 00244 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00245 # This is opposite to usual conventions but remains for\n\ 00246 # historical reasons. The newer PointCloud2 message has no\n\ 00247 # such problem.\n\ 00248 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00249 # (R,G,B) values packed into the least significant 24 bits,\n\ 00250 # in order.\n\ 00251 # \"intensity\" - laser or pixel intensity.\n\ 00252 # \"distance\"\n\ 00253 \n\ 00254 # The channel name should give semantics of the channel (e.g.\n\ 00255 # \"intensity\" instead of \"value\").\n\ 00256 string name\n\ 00257 \n\ 00258 # The values array should be 1-1 with the elements of the associated\n\ 00259 # PointCloud.\n\ 00260 float32[] values\n\ 00261 \n\ 00262 "; } 00263 public: 00264 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00265 00266 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00267 00268 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00269 { 00270 ros::serialization::OStream stream(write_ptr, 1000000000); 00271 ros::serialization::serialize(stream, table); 00272 ros::serialization::serialize(stream, clusters); 00273 ros::serialization::serialize(stream, num_models); 00274 ros::serialization::serialize(stream, perform_fit_merge); 00275 return stream.getData(); 00276 } 00277 00278 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00279 { 00280 ros::serialization::IStream stream(read_ptr, 1000000000); 00281 ros::serialization::deserialize(stream, table); 00282 ros::serialization::deserialize(stream, clusters); 00283 ros::serialization::deserialize(stream, num_models); 00284 ros::serialization::deserialize(stream, perform_fit_merge); 00285 return stream.getData(); 00286 } 00287 00288 ROS_DEPRECATED virtual uint32_t serializationLength() const 00289 { 00290 uint32_t size = 0; 00291 size += ros::serialization::serializationLength(table); 00292 size += ros::serialization::serializationLength(clusters); 00293 size += ros::serialization::serializationLength(num_models); 00294 size += ros::serialization::serializationLength(perform_fit_merge); 00295 return size; 00296 } 00297 00298 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > Ptr; 00299 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> const> ConstPtr; 00300 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00301 }; // struct TabletopObjectRecognitionRequest 00302 typedef ::tabletop_object_detector::TabletopObjectRecognitionRequest_<std::allocator<void> > TabletopObjectRecognitionRequest; 00303 00304 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionRequest> TabletopObjectRecognitionRequestPtr; 00305 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionRequest const> TabletopObjectRecognitionRequestConstPtr; 00306 00307 00308 template <class ContainerAllocator> 00309 struct TabletopObjectRecognitionResponse_ { 00310 typedef TabletopObjectRecognitionResponse_<ContainerAllocator> Type; 00311 00312 TabletopObjectRecognitionResponse_() 00313 : models() 00314 , cluster_model_indices() 00315 { 00316 } 00317 00318 TabletopObjectRecognitionResponse_(const ContainerAllocator& _alloc) 00319 : models(_alloc) 00320 , cluster_model_indices(_alloc) 00321 { 00322 } 00323 00324 typedef std::vector< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> >::other > _models_type; 00325 std::vector< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> >::other > models; 00326 00327 typedef std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > _cluster_model_indices_type; 00328 std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > cluster_model_indices; 00329 00330 00331 ROS_DEPRECATED uint32_t get_models_size() const { return (uint32_t)models.size(); } 00332 ROS_DEPRECATED void set_models_size(uint32_t size) { models.resize((size_t)size); } 00333 ROS_DEPRECATED void get_models_vec(std::vector< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> >::other > & vec) const { vec = this->models; } 00334 ROS_DEPRECATED void set_models_vec(const std::vector< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::household_objects_database_msgs::DatabaseModelPoseList_<ContainerAllocator> >::other > & vec) { this->models = vec; } 00335 ROS_DEPRECATED uint32_t get_cluster_model_indices_size() const { return (uint32_t)cluster_model_indices.size(); } 00336 ROS_DEPRECATED void set_cluster_model_indices_size(uint32_t size) { cluster_model_indices.resize((size_t)size); } 00337 ROS_DEPRECATED void get_cluster_model_indices_vec(std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > & vec) const { vec = this->cluster_model_indices; } 00338 ROS_DEPRECATED void set_cluster_model_indices_vec(const std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > & vec) { this->cluster_model_indices = vec; } 00339 private: 00340 static const char* __s_getDataType_() { return "tabletop_object_detector/TabletopObjectRecognitionResponse"; } 00341 public: 00342 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00343 00344 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00345 00346 private: 00347 static const char* __s_getMD5Sum_() { return "f63a7c7df1c6f8db6a82e83c1186e00e"; } 00348 public: 00349 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00350 00351 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00352 00353 private: 00354 static const char* __s_getServerMD5Sum_() { return "f5867bc89b17633ae48681b939f1fbf7"; } 00355 public: 00356 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00357 00358 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00359 00360 private: 00361 static const char* __s_getMessageDefinition_() { return "\n\ 00362 \n\ 00363 household_objects_database_msgs/DatabaseModelPoseList[] models\n\ 00364 \n\ 00365 \n\ 00366 \n\ 00367 int32[] cluster_model_indices\n\ 00368 \n\ 00369 \n\ 00370 ================================================================================\n\ 00371 MSG: household_objects_database_msgs/DatabaseModelPoseList\n\ 00372 # stores a list of possible database models recognition results\n\ 00373 DatabaseModelPose[] model_list\n\ 00374 ================================================================================\n\ 00375 MSG: household_objects_database_msgs/DatabaseModelPose\n\ 00376 # Informs that a specific model from the Model Database has been \n\ 00377 # identified at a certain location\n\ 00378 \n\ 00379 # the database id of the model\n\ 00380 int32 model_id\n\ 00381 \n\ 00382 # the pose that it can be found in\n\ 00383 geometry_msgs/PoseStamped pose\n\ 00384 \n\ 00385 # a measure of the confidence level in this detection result\n\ 00386 float32 confidence\n\ 00387 \n\ 00388 # the name of the object detector that generated this detection result\n\ 00389 string detector_name\n\ 00390 \n\ 00391 ================================================================================\n\ 00392 MSG: geometry_msgs/PoseStamped\n\ 00393 # A Pose with reference coordinate frame and timestamp\n\ 00394 Header header\n\ 00395 Pose pose\n\ 00396 \n\ 00397 ================================================================================\n\ 00398 MSG: std_msgs/Header\n\ 00399 # Standard metadata for higher-level stamped data types.\n\ 00400 # This is generally used to communicate timestamped data \n\ 00401 # in a particular coordinate frame.\n\ 00402 # \n\ 00403 # sequence ID: consecutively increasing ID \n\ 00404 uint32 seq\n\ 00405 #Two-integer timestamp that is expressed as:\n\ 00406 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00407 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00408 # time-handling sugar is provided by the client library\n\ 00409 time stamp\n\ 00410 #Frame this data is associated with\n\ 00411 # 0: no frame\n\ 00412 # 1: global frame\n\ 00413 string frame_id\n\ 00414 \n\ 00415 ================================================================================\n\ 00416 MSG: geometry_msgs/Pose\n\ 00417 # A representation of pose in free space, composed of postion and orientation. \n\ 00418 Point position\n\ 00419 Quaternion orientation\n\ 00420 \n\ 00421 ================================================================================\n\ 00422 MSG: geometry_msgs/Point\n\ 00423 # This contains the position of a point in free space\n\ 00424 float64 x\n\ 00425 float64 y\n\ 00426 float64 z\n\ 00427 \n\ 00428 ================================================================================\n\ 00429 MSG: geometry_msgs/Quaternion\n\ 00430 # This represents an orientation in free space in quaternion form.\n\ 00431 \n\ 00432 float64 x\n\ 00433 float64 y\n\ 00434 float64 z\n\ 00435 float64 w\n\ 00436 \n\ 00437 "; } 00438 public: 00439 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00440 00441 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00442 00443 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00444 { 00445 ros::serialization::OStream stream(write_ptr, 1000000000); 00446 ros::serialization::serialize(stream, models); 00447 ros::serialization::serialize(stream, cluster_model_indices); 00448 return stream.getData(); 00449 } 00450 00451 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00452 { 00453 ros::serialization::IStream stream(read_ptr, 1000000000); 00454 ros::serialization::deserialize(stream, models); 00455 ros::serialization::deserialize(stream, cluster_model_indices); 00456 return stream.getData(); 00457 } 00458 00459 ROS_DEPRECATED virtual uint32_t serializationLength() const 00460 { 00461 uint32_t size = 0; 00462 size += ros::serialization::serializationLength(models); 00463 size += ros::serialization::serializationLength(cluster_model_indices); 00464 return size; 00465 } 00466 00467 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > Ptr; 00468 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> const> ConstPtr; 00469 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00470 }; // struct TabletopObjectRecognitionResponse 00471 typedef ::tabletop_object_detector::TabletopObjectRecognitionResponse_<std::allocator<void> > TabletopObjectRecognitionResponse; 00472 00473 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionResponse> TabletopObjectRecognitionResponsePtr; 00474 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopObjectRecognitionResponse const> TabletopObjectRecognitionResponseConstPtr; 00475 00476 struct TabletopObjectRecognition 00477 { 00478 00479 typedef TabletopObjectRecognitionRequest Request; 00480 typedef TabletopObjectRecognitionResponse Response; 00481 Request request; 00482 Response response; 00483 00484 typedef Request RequestType; 00485 typedef Response ResponseType; 00486 }; // struct TabletopObjectRecognition 00487 } // namespace tabletop_object_detector 00488 00489 namespace ros 00490 { 00491 namespace message_traits 00492 { 00493 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > : public TrueType {}; 00494 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> const> : public TrueType {}; 00495 template<class ContainerAllocator> 00496 struct MD5Sum< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > { 00497 static const char* value() 00498 { 00499 return "197bf138763e73e721e55b16fedc33a9"; 00500 } 00501 00502 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> &) { return value(); } 00503 static const uint64_t static_value1 = 0x197bf138763e73e7ULL; 00504 static const uint64_t static_value2 = 0x21e55b16fedc33a9ULL; 00505 }; 00506 00507 template<class ContainerAllocator> 00508 struct DataType< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > { 00509 static const char* value() 00510 { 00511 return "tabletop_object_detector/TabletopObjectRecognitionRequest"; 00512 } 00513 00514 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> &) { return value(); } 00515 }; 00516 00517 template<class ContainerAllocator> 00518 struct Definition< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > { 00519 static const char* value() 00520 { 00521 return "\n\ 00522 Table table\n\ 00523 \n\ 00524 \n\ 00525 sensor_msgs/PointCloud[] clusters\n\ 00526 \n\ 00527 \n\ 00528 int32 num_models\n\ 00529 \n\ 00530 \n\ 00531 bool perform_fit_merge\n\ 00532 \n\ 00533 \n\ 00534 ================================================================================\n\ 00535 MSG: tabletop_object_detector/Table\n\ 00536 # Informs that a planar table has been detected at a given location\n\ 00537 \n\ 00538 # The pose gives you the transform that take you to the coordinate system\n\ 00539 # of the table, with the origin somewhere in the table plane and the \n\ 00540 # z axis normal to the plane\n\ 00541 geometry_msgs/PoseStamped pose\n\ 00542 \n\ 00543 # These values give you the observed extents of the table, along x and y,\n\ 00544 # in the table's own coordinate system (above)\n\ 00545 # there is no guarantee that the origin of the table coordinate system is\n\ 00546 # inside the boundary defined by these values. \n\ 00547 float32 x_min\n\ 00548 float32 x_max\n\ 00549 float32 y_min\n\ 00550 float32 y_max\n\ 00551 \n\ 00552 # There is no guarantee that the table does NOT extend further than these \n\ 00553 # values; this is just as far as we've observed it.\n\ 00554 \n\ 00555 \n\ 00556 # Newer table definition as triangle mesh of convex hull (relative to pose)\n\ 00557 arm_navigation_msgs/Shape convex_hull\n\ 00558 \n\ 00559 ================================================================================\n\ 00560 MSG: geometry_msgs/PoseStamped\n\ 00561 # A Pose with reference coordinate frame and timestamp\n\ 00562 Header header\n\ 00563 Pose pose\n\ 00564 \n\ 00565 ================================================================================\n\ 00566 MSG: std_msgs/Header\n\ 00567 # Standard metadata for higher-level stamped data types.\n\ 00568 # This is generally used to communicate timestamped data \n\ 00569 # in a particular coordinate frame.\n\ 00570 # \n\ 00571 # sequence ID: consecutively increasing ID \n\ 00572 uint32 seq\n\ 00573 #Two-integer timestamp that is expressed as:\n\ 00574 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00575 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00576 # time-handling sugar is provided by the client library\n\ 00577 time stamp\n\ 00578 #Frame this data is associated with\n\ 00579 # 0: no frame\n\ 00580 # 1: global frame\n\ 00581 string frame_id\n\ 00582 \n\ 00583 ================================================================================\n\ 00584 MSG: geometry_msgs/Pose\n\ 00585 # A representation of pose in free space, composed of postion and orientation. \n\ 00586 Point position\n\ 00587 Quaternion orientation\n\ 00588 \n\ 00589 ================================================================================\n\ 00590 MSG: geometry_msgs/Point\n\ 00591 # This contains the position of a point in free space\n\ 00592 float64 x\n\ 00593 float64 y\n\ 00594 float64 z\n\ 00595 \n\ 00596 ================================================================================\n\ 00597 MSG: geometry_msgs/Quaternion\n\ 00598 # This represents an orientation in free space in quaternion form.\n\ 00599 \n\ 00600 float64 x\n\ 00601 float64 y\n\ 00602 float64 z\n\ 00603 float64 w\n\ 00604 \n\ 00605 ================================================================================\n\ 00606 MSG: arm_navigation_msgs/Shape\n\ 00607 byte SPHERE=0\n\ 00608 byte BOX=1\n\ 00609 byte CYLINDER=2\n\ 00610 byte MESH=3\n\ 00611 \n\ 00612 byte type\n\ 00613 \n\ 00614 \n\ 00615 #### define sphere, box, cylinder ####\n\ 00616 # the origin of each shape is considered at the shape's center\n\ 00617 \n\ 00618 # for sphere\n\ 00619 # radius := dimensions[0]\n\ 00620 \n\ 00621 # for cylinder\n\ 00622 # radius := dimensions[0]\n\ 00623 # length := dimensions[1]\n\ 00624 # the length is along the Z axis\n\ 00625 \n\ 00626 # for box\n\ 00627 # size_x := dimensions[0]\n\ 00628 # size_y := dimensions[1]\n\ 00629 # size_z := dimensions[2]\n\ 00630 float64[] dimensions\n\ 00631 \n\ 00632 \n\ 00633 #### define mesh ####\n\ 00634 \n\ 00635 # list of triangles; triangle k is defined by tre vertices located\n\ 00636 # at indices triangles[3k], triangles[3k+1], triangles[3k+2]\n\ 00637 int32[] triangles\n\ 00638 geometry_msgs/Point[] vertices\n\ 00639 \n\ 00640 ================================================================================\n\ 00641 MSG: sensor_msgs/PointCloud\n\ 00642 # This message holds a collection of 3d points, plus optional additional\n\ 00643 # information about each point.\n\ 00644 \n\ 00645 # Time of sensor data acquisition, coordinate frame ID.\n\ 00646 Header header\n\ 00647 \n\ 00648 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ 00649 # in the frame given in the header.\n\ 00650 geometry_msgs/Point32[] points\n\ 00651 \n\ 00652 # Each channel should have the same number of elements as points array,\n\ 00653 # and the data in each channel should correspond 1:1 with each point.\n\ 00654 # Channel names in common practice are listed in ChannelFloat32.msg.\n\ 00655 ChannelFloat32[] channels\n\ 00656 \n\ 00657 ================================================================================\n\ 00658 MSG: geometry_msgs/Point32\n\ 00659 # This contains the position of a point in free space(with 32 bits of precision).\n\ 00660 # It is recommeded to use Point wherever possible instead of Point32. \n\ 00661 # \n\ 00662 # This recommendation is to promote interoperability. \n\ 00663 #\n\ 00664 # This message is designed to take up less space when sending\n\ 00665 # lots of points at once, as in the case of a PointCloud. \n\ 00666 \n\ 00667 float32 x\n\ 00668 float32 y\n\ 00669 float32 z\n\ 00670 ================================================================================\n\ 00671 MSG: sensor_msgs/ChannelFloat32\n\ 00672 # This message is used by the PointCloud message to hold optional data\n\ 00673 # associated with each point in the cloud. The length of the values\n\ 00674 # array should be the same as the length of the points array in the\n\ 00675 # PointCloud, and each value should be associated with the corresponding\n\ 00676 # point.\n\ 00677 \n\ 00678 # Channel names in existing practice include:\n\ 00679 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ 00680 # This is opposite to usual conventions but remains for\n\ 00681 # historical reasons. The newer PointCloud2 message has no\n\ 00682 # such problem.\n\ 00683 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ 00684 # (R,G,B) values packed into the least significant 24 bits,\n\ 00685 # in order.\n\ 00686 # \"intensity\" - laser or pixel intensity.\n\ 00687 # \"distance\"\n\ 00688 \n\ 00689 # The channel name should give semantics of the channel (e.g.\n\ 00690 # \"intensity\" instead of \"value\").\n\ 00691 string name\n\ 00692 \n\ 00693 # The values array should be 1-1 with the elements of the associated\n\ 00694 # PointCloud.\n\ 00695 float32[] values\n\ 00696 \n\ 00697 "; 00698 } 00699 00700 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> &) { return value(); } 00701 }; 00702 00703 } // namespace message_traits 00704 } // namespace ros 00705 00706 00707 namespace ros 00708 { 00709 namespace message_traits 00710 { 00711 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > : public TrueType {}; 00712 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> const> : public TrueType {}; 00713 template<class ContainerAllocator> 00714 struct MD5Sum< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > { 00715 static const char* value() 00716 { 00717 return "f63a7c7df1c6f8db6a82e83c1186e00e"; 00718 } 00719 00720 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> &) { return value(); } 00721 static const uint64_t static_value1 = 0xf63a7c7df1c6f8dbULL; 00722 static const uint64_t static_value2 = 0x6a82e83c1186e00eULL; 00723 }; 00724 00725 template<class ContainerAllocator> 00726 struct DataType< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > { 00727 static const char* value() 00728 { 00729 return "tabletop_object_detector/TabletopObjectRecognitionResponse"; 00730 } 00731 00732 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> &) { return value(); } 00733 }; 00734 00735 template<class ContainerAllocator> 00736 struct Definition< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > { 00737 static const char* value() 00738 { 00739 return "\n\ 00740 \n\ 00741 household_objects_database_msgs/DatabaseModelPoseList[] models\n\ 00742 \n\ 00743 \n\ 00744 \n\ 00745 int32[] cluster_model_indices\n\ 00746 \n\ 00747 \n\ 00748 ================================================================================\n\ 00749 MSG: household_objects_database_msgs/DatabaseModelPoseList\n\ 00750 # stores a list of possible database models recognition results\n\ 00751 DatabaseModelPose[] model_list\n\ 00752 ================================================================================\n\ 00753 MSG: household_objects_database_msgs/DatabaseModelPose\n\ 00754 # Informs that a specific model from the Model Database has been \n\ 00755 # identified at a certain location\n\ 00756 \n\ 00757 # the database id of the model\n\ 00758 int32 model_id\n\ 00759 \n\ 00760 # the pose that it can be found in\n\ 00761 geometry_msgs/PoseStamped pose\n\ 00762 \n\ 00763 # a measure of the confidence level in this detection result\n\ 00764 float32 confidence\n\ 00765 \n\ 00766 # the name of the object detector that generated this detection result\n\ 00767 string detector_name\n\ 00768 \n\ 00769 ================================================================================\n\ 00770 MSG: geometry_msgs/PoseStamped\n\ 00771 # A Pose with reference coordinate frame and timestamp\n\ 00772 Header header\n\ 00773 Pose pose\n\ 00774 \n\ 00775 ================================================================================\n\ 00776 MSG: std_msgs/Header\n\ 00777 # Standard metadata for higher-level stamped data types.\n\ 00778 # This is generally used to communicate timestamped data \n\ 00779 # in a particular coordinate frame.\n\ 00780 # \n\ 00781 # sequence ID: consecutively increasing ID \n\ 00782 uint32 seq\n\ 00783 #Two-integer timestamp that is expressed as:\n\ 00784 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00785 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00786 # time-handling sugar is provided by the client library\n\ 00787 time stamp\n\ 00788 #Frame this data is associated with\n\ 00789 # 0: no frame\n\ 00790 # 1: global frame\n\ 00791 string frame_id\n\ 00792 \n\ 00793 ================================================================================\n\ 00794 MSG: geometry_msgs/Pose\n\ 00795 # A representation of pose in free space, composed of postion and orientation. \n\ 00796 Point position\n\ 00797 Quaternion orientation\n\ 00798 \n\ 00799 ================================================================================\n\ 00800 MSG: geometry_msgs/Point\n\ 00801 # This contains the position of a point in free space\n\ 00802 float64 x\n\ 00803 float64 y\n\ 00804 float64 z\n\ 00805 \n\ 00806 ================================================================================\n\ 00807 MSG: geometry_msgs/Quaternion\n\ 00808 # This represents an orientation in free space in quaternion form.\n\ 00809 \n\ 00810 float64 x\n\ 00811 float64 y\n\ 00812 float64 z\n\ 00813 float64 w\n\ 00814 \n\ 00815 "; 00816 } 00817 00818 static const char* value(const ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> &) { return value(); } 00819 }; 00820 00821 } // namespace message_traits 00822 } // namespace ros 00823 00824 namespace ros 00825 { 00826 namespace serialization 00827 { 00828 00829 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > 00830 { 00831 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00832 { 00833 stream.next(m.table); 00834 stream.next(m.clusters); 00835 stream.next(m.num_models); 00836 stream.next(m.perform_fit_merge); 00837 } 00838 00839 ROS_DECLARE_ALLINONE_SERIALIZER; 00840 }; // struct TabletopObjectRecognitionRequest_ 00841 } // namespace serialization 00842 } // namespace ros 00843 00844 00845 namespace ros 00846 { 00847 namespace serialization 00848 { 00849 00850 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > 00851 { 00852 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00853 { 00854 stream.next(m.models); 00855 stream.next(m.cluster_model_indices); 00856 } 00857 00858 ROS_DECLARE_ALLINONE_SERIALIZER; 00859 }; // struct TabletopObjectRecognitionResponse_ 00860 } // namespace serialization 00861 } // namespace ros 00862 00863 namespace ros 00864 { 00865 namespace service_traits 00866 { 00867 template<> 00868 struct MD5Sum<tabletop_object_detector::TabletopObjectRecognition> { 00869 static const char* value() 00870 { 00871 return "f5867bc89b17633ae48681b939f1fbf7"; 00872 } 00873 00874 static const char* value(const tabletop_object_detector::TabletopObjectRecognition&) { return value(); } 00875 }; 00876 00877 template<> 00878 struct DataType<tabletop_object_detector::TabletopObjectRecognition> { 00879 static const char* value() 00880 { 00881 return "tabletop_object_detector/TabletopObjectRecognition"; 00882 } 00883 00884 static const char* value(const tabletop_object_detector::TabletopObjectRecognition&) { return value(); } 00885 }; 00886 00887 template<class ContainerAllocator> 00888 struct MD5Sum<tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > { 00889 static const char* value() 00890 { 00891 return "f5867bc89b17633ae48681b939f1fbf7"; 00892 } 00893 00894 static const char* value(const tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> &) { return value(); } 00895 }; 00896 00897 template<class ContainerAllocator> 00898 struct DataType<tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> > { 00899 static const char* value() 00900 { 00901 return "tabletop_object_detector/TabletopObjectRecognition"; 00902 } 00903 00904 static const char* value(const tabletop_object_detector::TabletopObjectRecognitionRequest_<ContainerAllocator> &) { return value(); } 00905 }; 00906 00907 template<class ContainerAllocator> 00908 struct MD5Sum<tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > { 00909 static const char* value() 00910 { 00911 return "f5867bc89b17633ae48681b939f1fbf7"; 00912 } 00913 00914 static const char* value(const tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> &) { return value(); } 00915 }; 00916 00917 template<class ContainerAllocator> 00918 struct DataType<tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> > { 00919 static const char* value() 00920 { 00921 return "tabletop_object_detector/TabletopObjectRecognition"; 00922 } 00923 00924 static const char* value(const tabletop_object_detector::TabletopObjectRecognitionResponse_<ContainerAllocator> &) { return value(); } 00925 }; 00926 00927 } // namespace service_traits 00928 } // namespace ros 00929 00930 #endif // TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPOBJECTRECOGNITION_H 00931