$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-cob_object_perception/doc_stacks/2013-03-01_14-45-40.878742/cob_object_perception/cob_object_detection_msgs/srv/DetectObjects.srv */ 00002 #ifndef COB_OBJECT_DETECTION_MSGS_SERVICE_DETECTOBJECTS_H 00003 #define COB_OBJECT_DETECTION_MSGS_SERVICE_DETECTOBJECTS_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 "std_msgs/String.h" 00020 #include "sensor_msgs/RegionOfInterest.h" 00021 00022 00023 #include "cob_object_detection_msgs/DetectionArray.h" 00024 00025 namespace cob_object_detection_msgs 00026 { 00027 template <class ContainerAllocator> 00028 struct DetectObjectsRequest_ { 00029 typedef DetectObjectsRequest_<ContainerAllocator> Type; 00030 00031 DetectObjectsRequest_() 00032 : object_name() 00033 , roi() 00034 { 00035 } 00036 00037 DetectObjectsRequest_(const ContainerAllocator& _alloc) 00038 : object_name(_alloc) 00039 , roi(_alloc) 00040 { 00041 } 00042 00043 typedef ::std_msgs::String_<ContainerAllocator> _object_name_type; 00044 ::std_msgs::String_<ContainerAllocator> object_name; 00045 00046 typedef ::sensor_msgs::RegionOfInterest_<ContainerAllocator> _roi_type; 00047 ::sensor_msgs::RegionOfInterest_<ContainerAllocator> roi; 00048 00049 00050 private: 00051 static const char* __s_getDataType_() { return "cob_object_detection_msgs/DetectObjectsRequest"; } 00052 public: 00053 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00054 00055 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00056 00057 private: 00058 static const char* __s_getMD5Sum_() { return "8d651fac3fa327d154d291de842e3994"; } 00059 public: 00060 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00061 00062 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00063 00064 private: 00065 static const char* __s_getServerMD5Sum_() { return "3e7b1c8cc85eedd71f86f7179c8873b6"; } 00066 public: 00067 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00068 00069 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00070 00071 private: 00072 static const char* __s_getMessageDefinition_() { return "std_msgs/String object_name\n\ 00073 sensor_msgs/RegionOfInterest roi\n\ 00074 \n\ 00075 ================================================================================\n\ 00076 MSG: std_msgs/String\n\ 00077 string data\n\ 00078 \n\ 00079 ================================================================================\n\ 00080 MSG: sensor_msgs/RegionOfInterest\n\ 00081 # This message is used to specify a region of interest within an image.\n\ 00082 #\n\ 00083 # When used to specify the ROI setting of the camera when the image was\n\ 00084 # taken, the height and width fields should either match the height and\n\ 00085 # width fields for the associated image; or height = width = 0\n\ 00086 # indicates that the full resolution image was captured.\n\ 00087 \n\ 00088 uint32 x_offset # Leftmost pixel of the ROI\n\ 00089 # (0 if the ROI includes the left edge of the image)\n\ 00090 uint32 y_offset # Topmost pixel of the ROI\n\ 00091 # (0 if the ROI includes the top edge of the image)\n\ 00092 uint32 height # Height of ROI\n\ 00093 uint32 width # Width of ROI\n\ 00094 \n\ 00095 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\ 00096 # ROI in this message. Typically this should be False if the full image\n\ 00097 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\ 00098 # used).\n\ 00099 bool do_rectify\n\ 00100 \n\ 00101 "; } 00102 public: 00103 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00104 00105 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00106 00107 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00108 { 00109 ros::serialization::OStream stream(write_ptr, 1000000000); 00110 ros::serialization::serialize(stream, object_name); 00111 ros::serialization::serialize(stream, roi); 00112 return stream.getData(); 00113 } 00114 00115 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00116 { 00117 ros::serialization::IStream stream(read_ptr, 1000000000); 00118 ros::serialization::deserialize(stream, object_name); 00119 ros::serialization::deserialize(stream, roi); 00120 return stream.getData(); 00121 } 00122 00123 ROS_DEPRECATED virtual uint32_t serializationLength() const 00124 { 00125 uint32_t size = 0; 00126 size += ros::serialization::serializationLength(object_name); 00127 size += ros::serialization::serializationLength(roi); 00128 return size; 00129 } 00130 00131 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > Ptr; 00132 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> const> ConstPtr; 00133 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00134 }; // struct DetectObjectsRequest 00135 typedef ::cob_object_detection_msgs::DetectObjectsRequest_<std::allocator<void> > DetectObjectsRequest; 00136 00137 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsRequest> DetectObjectsRequestPtr; 00138 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsRequest const> DetectObjectsRequestConstPtr; 00139 00140 00141 template <class ContainerAllocator> 00142 struct DetectObjectsResponse_ { 00143 typedef DetectObjectsResponse_<ContainerAllocator> Type; 00144 00145 DetectObjectsResponse_() 00146 : object_list() 00147 { 00148 } 00149 00150 DetectObjectsResponse_(const ContainerAllocator& _alloc) 00151 : object_list(_alloc) 00152 { 00153 } 00154 00155 typedef ::cob_object_detection_msgs::DetectionArray_<ContainerAllocator> _object_list_type; 00156 ::cob_object_detection_msgs::DetectionArray_<ContainerAllocator> object_list; 00157 00158 00159 private: 00160 static const char* __s_getDataType_() { return "cob_object_detection_msgs/DetectObjectsResponse"; } 00161 public: 00162 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00163 00164 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00165 00166 private: 00167 static const char* __s_getMD5Sum_() { return "6e46a64486bc23cca1c161460b4c92b6"; } 00168 public: 00169 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00170 00171 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00172 00173 private: 00174 static const char* __s_getServerMD5Sum_() { return "3e7b1c8cc85eedd71f86f7179c8873b6"; } 00175 public: 00176 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); } 00177 00178 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); } 00179 00180 private: 00181 static const char* __s_getMessageDefinition_() { return "cob_object_detection_msgs/DetectionArray object_list\n\ 00182 \n\ 00183 \n\ 00184 ================================================================================\n\ 00185 MSG: cob_object_detection_msgs/DetectionArray\n\ 00186 Header header\n\ 00187 Detection[] detections\n\ 00188 \n\ 00189 ================================================================================\n\ 00190 MSG: std_msgs/Header\n\ 00191 # Standard metadata for higher-level stamped data types.\n\ 00192 # This is generally used to communicate timestamped data \n\ 00193 # in a particular coordinate frame.\n\ 00194 # \n\ 00195 # sequence ID: consecutively increasing ID \n\ 00196 uint32 seq\n\ 00197 #Two-integer timestamp that is expressed as:\n\ 00198 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00199 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00200 # time-handling sugar is provided by the client library\n\ 00201 time stamp\n\ 00202 #Frame this data is associated with\n\ 00203 # 0: no frame\n\ 00204 # 1: global frame\n\ 00205 string frame_id\n\ 00206 \n\ 00207 ================================================================================\n\ 00208 MSG: cob_object_detection_msgs/Detection\n\ 00209 Header header\n\ 00210 string label\n\ 00211 string detector\n\ 00212 float32 score\n\ 00213 Mask mask\n\ 00214 geometry_msgs/PoseStamped pose\n\ 00215 geometry_msgs/Point bounding_box_lwh\n\ 00216 \n\ 00217 ================================================================================\n\ 00218 MSG: cob_object_detection_msgs/Mask\n\ 00219 # this message is used to mark where an object is present in an image\n\ 00220 # this can be done either by a roi region on the image (less precise) or a mask (more precise)\n\ 00221 \n\ 00222 Rect roi\n\ 00223 \n\ 00224 # in the case when mask is used, 'roi' specifies the image region and 'mask'\n\ 00225 # (which should be of the same size) a binary mask in that region\n\ 00226 sensor_msgs/Image mask\n\ 00227 \n\ 00228 # in the case there is 3D data available, 'indices' are used to index the \n\ 00229 # part of the point cloud representing the object\n\ 00230 #pcl/PointIndices indices\n\ 00231 \n\ 00232 ================================================================================\n\ 00233 MSG: cob_object_detection_msgs/Rect\n\ 00234 int32 x\n\ 00235 int32 y\n\ 00236 int32 width\n\ 00237 int32 height\n\ 00238 \n\ 00239 ================================================================================\n\ 00240 MSG: sensor_msgs/Image\n\ 00241 # This message contains an uncompressed image\n\ 00242 # (0, 0) is at top-left corner of image\n\ 00243 #\n\ 00244 \n\ 00245 Header header # Header timestamp should be acquisition time of image\n\ 00246 # Header frame_id should be optical frame of camera\n\ 00247 # origin of frame should be optical center of cameara\n\ 00248 # +x should point to the right in the image\n\ 00249 # +y should point down in the image\n\ 00250 # +z should point into to plane of the image\n\ 00251 # If the frame_id here and the frame_id of the CameraInfo\n\ 00252 # message associated with the image conflict\n\ 00253 # the behavior is undefined\n\ 00254 \n\ 00255 uint32 height # image height, that is, number of rows\n\ 00256 uint32 width # image width, that is, number of columns\n\ 00257 \n\ 00258 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00259 # If you want to standardize a new string format, join\n\ 00260 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00261 \n\ 00262 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00263 # taken from the list of strings in src/image_encodings.cpp\n\ 00264 \n\ 00265 uint8 is_bigendian # is this data bigendian?\n\ 00266 uint32 step # Full row length in bytes\n\ 00267 uint8[] data # actual matrix data, size is (step * rows)\n\ 00268 \n\ 00269 ================================================================================\n\ 00270 MSG: geometry_msgs/PoseStamped\n\ 00271 # A Pose with reference coordinate frame and timestamp\n\ 00272 Header header\n\ 00273 Pose pose\n\ 00274 \n\ 00275 ================================================================================\n\ 00276 MSG: geometry_msgs/Pose\n\ 00277 # A representation of pose in free space, composed of postion and orientation. \n\ 00278 Point position\n\ 00279 Quaternion orientation\n\ 00280 \n\ 00281 ================================================================================\n\ 00282 MSG: geometry_msgs/Point\n\ 00283 # This contains the position of a point in free space\n\ 00284 float64 x\n\ 00285 float64 y\n\ 00286 float64 z\n\ 00287 \n\ 00288 ================================================================================\n\ 00289 MSG: geometry_msgs/Quaternion\n\ 00290 # This represents an orientation in free space in quaternion form.\n\ 00291 \n\ 00292 float64 x\n\ 00293 float64 y\n\ 00294 float64 z\n\ 00295 float64 w\n\ 00296 \n\ 00297 "; } 00298 public: 00299 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00300 00301 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00302 00303 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00304 { 00305 ros::serialization::OStream stream(write_ptr, 1000000000); 00306 ros::serialization::serialize(stream, object_list); 00307 return stream.getData(); 00308 } 00309 00310 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00311 { 00312 ros::serialization::IStream stream(read_ptr, 1000000000); 00313 ros::serialization::deserialize(stream, object_list); 00314 return stream.getData(); 00315 } 00316 00317 ROS_DEPRECATED virtual uint32_t serializationLength() const 00318 { 00319 uint32_t size = 0; 00320 size += ros::serialization::serializationLength(object_list); 00321 return size; 00322 } 00323 00324 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > Ptr; 00325 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> const> ConstPtr; 00326 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00327 }; // struct DetectObjectsResponse 00328 typedef ::cob_object_detection_msgs::DetectObjectsResponse_<std::allocator<void> > DetectObjectsResponse; 00329 00330 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsResponse> DetectObjectsResponsePtr; 00331 typedef boost::shared_ptr< ::cob_object_detection_msgs::DetectObjectsResponse const> DetectObjectsResponseConstPtr; 00332 00333 struct DetectObjects 00334 { 00335 00336 typedef DetectObjectsRequest Request; 00337 typedef DetectObjectsResponse Response; 00338 Request request; 00339 Response response; 00340 00341 typedef Request RequestType; 00342 typedef Response ResponseType; 00343 }; // struct DetectObjects 00344 } // namespace cob_object_detection_msgs 00345 00346 namespace ros 00347 { 00348 namespace message_traits 00349 { 00350 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > : public TrueType {}; 00351 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> const> : public TrueType {}; 00352 template<class ContainerAllocator> 00353 struct MD5Sum< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > { 00354 static const char* value() 00355 { 00356 return "8d651fac3fa327d154d291de842e3994"; 00357 } 00358 00359 static const char* value(const ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> &) { return value(); } 00360 static const uint64_t static_value1 = 0x8d651fac3fa327d1ULL; 00361 static const uint64_t static_value2 = 0x54d291de842e3994ULL; 00362 }; 00363 00364 template<class ContainerAllocator> 00365 struct DataType< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > { 00366 static const char* value() 00367 { 00368 return "cob_object_detection_msgs/DetectObjectsRequest"; 00369 } 00370 00371 static const char* value(const ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> &) { return value(); } 00372 }; 00373 00374 template<class ContainerAllocator> 00375 struct Definition< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > { 00376 static const char* value() 00377 { 00378 return "std_msgs/String object_name\n\ 00379 sensor_msgs/RegionOfInterest roi\n\ 00380 \n\ 00381 ================================================================================\n\ 00382 MSG: std_msgs/String\n\ 00383 string data\n\ 00384 \n\ 00385 ================================================================================\n\ 00386 MSG: sensor_msgs/RegionOfInterest\n\ 00387 # This message is used to specify a region of interest within an image.\n\ 00388 #\n\ 00389 # When used to specify the ROI setting of the camera when the image was\n\ 00390 # taken, the height and width fields should either match the height and\n\ 00391 # width fields for the associated image; or height = width = 0\n\ 00392 # indicates that the full resolution image was captured.\n\ 00393 \n\ 00394 uint32 x_offset # Leftmost pixel of the ROI\n\ 00395 # (0 if the ROI includes the left edge of the image)\n\ 00396 uint32 y_offset # Topmost pixel of the ROI\n\ 00397 # (0 if the ROI includes the top edge of the image)\n\ 00398 uint32 height # Height of ROI\n\ 00399 uint32 width # Width of ROI\n\ 00400 \n\ 00401 # True if a distinct rectified ROI should be calculated from the \"raw\"\n\ 00402 # ROI in this message. Typically this should be False if the full image\n\ 00403 # is captured (ROI not used), and True if a subwindow is captured (ROI\n\ 00404 # used).\n\ 00405 bool do_rectify\n\ 00406 \n\ 00407 "; 00408 } 00409 00410 static const char* value(const ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> &) { return value(); } 00411 }; 00412 00413 } // namespace message_traits 00414 } // namespace ros 00415 00416 00417 namespace ros 00418 { 00419 namespace message_traits 00420 { 00421 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > : public TrueType {}; 00422 template<class ContainerAllocator> struct IsMessage< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> const> : public TrueType {}; 00423 template<class ContainerAllocator> 00424 struct MD5Sum< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > { 00425 static const char* value() 00426 { 00427 return "6e46a64486bc23cca1c161460b4c92b6"; 00428 } 00429 00430 static const char* value(const ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> &) { return value(); } 00431 static const uint64_t static_value1 = 0x6e46a64486bc23ccULL; 00432 static const uint64_t static_value2 = 0xa1c161460b4c92b6ULL; 00433 }; 00434 00435 template<class ContainerAllocator> 00436 struct DataType< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > { 00437 static const char* value() 00438 { 00439 return "cob_object_detection_msgs/DetectObjectsResponse"; 00440 } 00441 00442 static const char* value(const ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> &) { return value(); } 00443 }; 00444 00445 template<class ContainerAllocator> 00446 struct Definition< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > { 00447 static const char* value() 00448 { 00449 return "cob_object_detection_msgs/DetectionArray object_list\n\ 00450 \n\ 00451 \n\ 00452 ================================================================================\n\ 00453 MSG: cob_object_detection_msgs/DetectionArray\n\ 00454 Header header\n\ 00455 Detection[] detections\n\ 00456 \n\ 00457 ================================================================================\n\ 00458 MSG: std_msgs/Header\n\ 00459 # Standard metadata for higher-level stamped data types.\n\ 00460 # This is generally used to communicate timestamped data \n\ 00461 # in a particular coordinate frame.\n\ 00462 # \n\ 00463 # sequence ID: consecutively increasing ID \n\ 00464 uint32 seq\n\ 00465 #Two-integer timestamp that is expressed as:\n\ 00466 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00467 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00468 # time-handling sugar is provided by the client library\n\ 00469 time stamp\n\ 00470 #Frame this data is associated with\n\ 00471 # 0: no frame\n\ 00472 # 1: global frame\n\ 00473 string frame_id\n\ 00474 \n\ 00475 ================================================================================\n\ 00476 MSG: cob_object_detection_msgs/Detection\n\ 00477 Header header\n\ 00478 string label\n\ 00479 string detector\n\ 00480 float32 score\n\ 00481 Mask mask\n\ 00482 geometry_msgs/PoseStamped pose\n\ 00483 geometry_msgs/Point bounding_box_lwh\n\ 00484 \n\ 00485 ================================================================================\n\ 00486 MSG: cob_object_detection_msgs/Mask\n\ 00487 # this message is used to mark where an object is present in an image\n\ 00488 # this can be done either by a roi region on the image (less precise) or a mask (more precise)\n\ 00489 \n\ 00490 Rect roi\n\ 00491 \n\ 00492 # in the case when mask is used, 'roi' specifies the image region and 'mask'\n\ 00493 # (which should be of the same size) a binary mask in that region\n\ 00494 sensor_msgs/Image mask\n\ 00495 \n\ 00496 # in the case there is 3D data available, 'indices' are used to index the \n\ 00497 # part of the point cloud representing the object\n\ 00498 #pcl/PointIndices indices\n\ 00499 \n\ 00500 ================================================================================\n\ 00501 MSG: cob_object_detection_msgs/Rect\n\ 00502 int32 x\n\ 00503 int32 y\n\ 00504 int32 width\n\ 00505 int32 height\n\ 00506 \n\ 00507 ================================================================================\n\ 00508 MSG: sensor_msgs/Image\n\ 00509 # This message contains an uncompressed image\n\ 00510 # (0, 0) is at top-left corner of image\n\ 00511 #\n\ 00512 \n\ 00513 Header header # Header timestamp should be acquisition time of image\n\ 00514 # Header frame_id should be optical frame of camera\n\ 00515 # origin of frame should be optical center of cameara\n\ 00516 # +x should point to the right in the image\n\ 00517 # +y should point down in the image\n\ 00518 # +z should point into to plane of the image\n\ 00519 # If the frame_id here and the frame_id of the CameraInfo\n\ 00520 # message associated with the image conflict\n\ 00521 # the behavior is undefined\n\ 00522 \n\ 00523 uint32 height # image height, that is, number of rows\n\ 00524 uint32 width # image width, that is, number of columns\n\ 00525 \n\ 00526 # The legal values for encoding are in file src/image_encodings.cpp\n\ 00527 # If you want to standardize a new string format, join\n\ 00528 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ 00529 \n\ 00530 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ 00531 # taken from the list of strings in src/image_encodings.cpp\n\ 00532 \n\ 00533 uint8 is_bigendian # is this data bigendian?\n\ 00534 uint32 step # Full row length in bytes\n\ 00535 uint8[] data # actual matrix data, size is (step * rows)\n\ 00536 \n\ 00537 ================================================================================\n\ 00538 MSG: geometry_msgs/PoseStamped\n\ 00539 # A Pose with reference coordinate frame and timestamp\n\ 00540 Header header\n\ 00541 Pose pose\n\ 00542 \n\ 00543 ================================================================================\n\ 00544 MSG: geometry_msgs/Pose\n\ 00545 # A representation of pose in free space, composed of postion and orientation. \n\ 00546 Point position\n\ 00547 Quaternion orientation\n\ 00548 \n\ 00549 ================================================================================\n\ 00550 MSG: geometry_msgs/Point\n\ 00551 # This contains the position of a point in free space\n\ 00552 float64 x\n\ 00553 float64 y\n\ 00554 float64 z\n\ 00555 \n\ 00556 ================================================================================\n\ 00557 MSG: geometry_msgs/Quaternion\n\ 00558 # This represents an orientation in free space in quaternion form.\n\ 00559 \n\ 00560 float64 x\n\ 00561 float64 y\n\ 00562 float64 z\n\ 00563 float64 w\n\ 00564 \n\ 00565 "; 00566 } 00567 00568 static const char* value(const ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> &) { return value(); } 00569 }; 00570 00571 } // namespace message_traits 00572 } // namespace ros 00573 00574 namespace ros 00575 { 00576 namespace serialization 00577 { 00578 00579 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > 00580 { 00581 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00582 { 00583 stream.next(m.object_name); 00584 stream.next(m.roi); 00585 } 00586 00587 ROS_DECLARE_ALLINONE_SERIALIZER; 00588 }; // struct DetectObjectsRequest_ 00589 } // namespace serialization 00590 } // namespace ros 00591 00592 00593 namespace ros 00594 { 00595 namespace serialization 00596 { 00597 00598 template<class ContainerAllocator> struct Serializer< ::cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > 00599 { 00600 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00601 { 00602 stream.next(m.object_list); 00603 } 00604 00605 ROS_DECLARE_ALLINONE_SERIALIZER; 00606 }; // struct DetectObjectsResponse_ 00607 } // namespace serialization 00608 } // namespace ros 00609 00610 namespace ros 00611 { 00612 namespace service_traits 00613 { 00614 template<> 00615 struct MD5Sum<cob_object_detection_msgs::DetectObjects> { 00616 static const char* value() 00617 { 00618 return "3e7b1c8cc85eedd71f86f7179c8873b6"; 00619 } 00620 00621 static const char* value(const cob_object_detection_msgs::DetectObjects&) { return value(); } 00622 }; 00623 00624 template<> 00625 struct DataType<cob_object_detection_msgs::DetectObjects> { 00626 static const char* value() 00627 { 00628 return "cob_object_detection_msgs/DetectObjects"; 00629 } 00630 00631 static const char* value(const cob_object_detection_msgs::DetectObjects&) { return value(); } 00632 }; 00633 00634 template<class ContainerAllocator> 00635 struct MD5Sum<cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > { 00636 static const char* value() 00637 { 00638 return "3e7b1c8cc85eedd71f86f7179c8873b6"; 00639 } 00640 00641 static const char* value(const cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> &) { return value(); } 00642 }; 00643 00644 template<class ContainerAllocator> 00645 struct DataType<cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> > { 00646 static const char* value() 00647 { 00648 return "cob_object_detection_msgs/DetectObjects"; 00649 } 00650 00651 static const char* value(const cob_object_detection_msgs::DetectObjectsRequest_<ContainerAllocator> &) { return value(); } 00652 }; 00653 00654 template<class ContainerAllocator> 00655 struct MD5Sum<cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > { 00656 static const char* value() 00657 { 00658 return "3e7b1c8cc85eedd71f86f7179c8873b6"; 00659 } 00660 00661 static const char* value(const cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> &) { return value(); } 00662 }; 00663 00664 template<class ContainerAllocator> 00665 struct DataType<cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> > { 00666 static const char* value() 00667 { 00668 return "cob_object_detection_msgs/DetectObjects"; 00669 } 00670 00671 static const char* value(const cob_object_detection_msgs::DetectObjectsResponse_<ContainerAllocator> &) { return value(); } 00672 }; 00673 00674 } // namespace service_traits 00675 } // namespace ros 00676 00677 #endif // COB_OBJECT_DETECTION_MSGS_SERVICE_DETECTOBJECTS_H 00678