00001
00002 #ifndef TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPSEGMENTATION_H
00003 #define TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPSEGMENTATION_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "ros/service_traits.h"
00014
00015
00016
00017 #include "tabletop_object_detector/Table.h"
00018 #include "sensor_msgs/PointCloud.h"
00019
00020 namespace tabletop_object_detector
00021 {
00022 template <class ContainerAllocator>
00023 struct TabletopSegmentationRequest_ : public ros::Message
00024 {
00025 typedef TabletopSegmentationRequest_<ContainerAllocator> Type;
00026
00027 TabletopSegmentationRequest_()
00028 {
00029 }
00030
00031 TabletopSegmentationRequest_(const ContainerAllocator& _alloc)
00032 {
00033 }
00034
00035
00036 private:
00037 static const char* __s_getDataType_() { return "tabletop_object_detector/TabletopSegmentationRequest"; }
00038 public:
00039 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00040
00041 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00042
00043 private:
00044 static const char* __s_getMD5Sum_() { return "d41d8cd98f00b204e9800998ecf8427e"; }
00045 public:
00046 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00047
00048 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00049
00050 private:
00051 static const char* __s_getServerMD5Sum_() { return "4e3320ac33e6de7047804c8f0f76efd0"; }
00052 public:
00053 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00054
00055 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00056
00057 private:
00058 static const char* __s_getMessageDefinition_() { return "\n\
00059 \n\
00060 \n\
00061 "; }
00062 public:
00063 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00064
00065 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00066
00067 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00068 {
00069 ros::serialization::OStream stream(write_ptr, 1000000000);
00070 return stream.getData();
00071 }
00072
00073 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00074 {
00075 ros::serialization::IStream stream(read_ptr, 1000000000);
00076 return stream.getData();
00077 }
00078
00079 ROS_DEPRECATED virtual uint32_t serializationLength() const
00080 {
00081 uint32_t size = 0;
00082 return size;
00083 }
00084
00085 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > Ptr;
00086 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> const> ConstPtr;
00087 };
00088 typedef ::tabletop_object_detector::TabletopSegmentationRequest_<std::allocator<void> > TabletopSegmentationRequest;
00089
00090 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest> TabletopSegmentationRequestPtr;
00091 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest const> TabletopSegmentationRequestConstPtr;
00092
00093
00094 template <class ContainerAllocator>
00095 struct TabletopSegmentationResponse_ : public ros::Message
00096 {
00097 typedef TabletopSegmentationResponse_<ContainerAllocator> Type;
00098
00099 TabletopSegmentationResponse_()
00100 : table()
00101 , clusters()
00102 , result(0)
00103 {
00104 }
00105
00106 TabletopSegmentationResponse_(const ContainerAllocator& _alloc)
00107 : table(_alloc)
00108 , clusters(_alloc)
00109 , result(0)
00110 {
00111 }
00112
00113 typedef ::tabletop_object_detector::Table_<ContainerAllocator> _table_type;
00114 ::tabletop_object_detector::Table_<ContainerAllocator> table;
00115
00116 typedef std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > _clusters_type;
00117 std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > clusters;
00118
00119 typedef int32_t _result_type;
00120 int32_t result;
00121
00122 enum { NO_CLOUD_RECEIVED = 1 };
00123 enum { NO_TABLE = 2 };
00124 enum { OTHER_ERROR = 3 };
00125 enum { SUCCESS = 4 };
00126
00127 ROS_DEPRECATED uint32_t get_clusters_size() const { return (uint32_t)clusters.size(); }
00128 ROS_DEPRECATED void set_clusters_size(uint32_t size) { clusters.resize((size_t)size); }
00129 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; }
00130 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; }
00131 private:
00132 static const char* __s_getDataType_() { return "tabletop_object_detector/TabletopSegmentationResponse"; }
00133 public:
00134 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00135
00136 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00137
00138 private:
00139 static const char* __s_getMD5Sum_() { return "4e3320ac33e6de7047804c8f0f76efd0"; }
00140 public:
00141 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00142
00143 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00144
00145 private:
00146 static const char* __s_getServerMD5Sum_() { return "4e3320ac33e6de7047804c8f0f76efd0"; }
00147 public:
00148 ROS_DEPRECATED static const std::string __s_getServerMD5Sum() { return __s_getServerMD5Sum_(); }
00149
00150 ROS_DEPRECATED const std::string __getServerMD5Sum() const { return __s_getServerMD5Sum_(); }
00151
00152 private:
00153 static const char* __s_getMessageDefinition_() { return "\n\
00154 \n\
00155 Table table\n\
00156 \n\
00157 \n\
00158 sensor_msgs/PointCloud[] clusters\n\
00159 \n\
00160 \n\
00161 int32 NO_CLOUD_RECEIVED = 1\n\
00162 int32 NO_TABLE = 2\n\
00163 int32 OTHER_ERROR = 3\n\
00164 int32 SUCCESS = 4\n\
00165 int32 result\n\
00166 \n\
00167 \n\
00168 ================================================================================\n\
00169 MSG: tabletop_object_detector/Table\n\
00170 # Informs that a planar table has been detected at a given location\n\
00171 \n\
00172 # The pose gives you the transform that take you to the coordinate system\n\
00173 # of the table, with the origin somewhere in the table plane and the \n\
00174 # z axis normal to the plane\n\
00175 geometry_msgs/PoseStamped pose\n\
00176 \n\
00177 # These values give you the observed extents of the table, along x and y,\n\
00178 # in the table's own coordinate system (above)\n\
00179 # there is no guarantee that the origin of the table coordinate system is\n\
00180 # inside the boundary defined by these values. \n\
00181 float32 x_min\n\
00182 float32 x_max\n\
00183 float32 y_min\n\
00184 float32 y_max\n\
00185 \n\
00186 # There is no guarantee that the table doe NOT extend further than these \n\
00187 # values; this is just as far as we've observed it.\n\
00188 \n\
00189 ================================================================================\n\
00190 MSG: geometry_msgs/PoseStamped\n\
00191 # A Pose with reference coordinate frame and timestamp\n\
00192 Header header\n\
00193 Pose pose\n\
00194 \n\
00195 ================================================================================\n\
00196 MSG: std_msgs/Header\n\
00197 # Standard metadata for higher-level stamped data types.\n\
00198 # This is generally used to communicate timestamped data \n\
00199 # in a particular coordinate frame.\n\
00200 # \n\
00201 # sequence ID: consecutively increasing ID \n\
00202 uint32 seq\n\
00203 #Two-integer timestamp that is expressed as:\n\
00204 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00205 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00206 # time-handling sugar is provided by the client library\n\
00207 time stamp\n\
00208 #Frame this data is associated with\n\
00209 # 0: no frame\n\
00210 # 1: global frame\n\
00211 string frame_id\n\
00212 \n\
00213 ================================================================================\n\
00214 MSG: geometry_msgs/Pose\n\
00215 # A representation of pose in free space, composed of postion and orientation. \n\
00216 Point position\n\
00217 Quaternion orientation\n\
00218 \n\
00219 ================================================================================\n\
00220 MSG: geometry_msgs/Point\n\
00221 # This contains the position of a point in free space\n\
00222 float64 x\n\
00223 float64 y\n\
00224 float64 z\n\
00225 \n\
00226 ================================================================================\n\
00227 MSG: geometry_msgs/Quaternion\n\
00228 # This represents an orientation in free space in quaternion form.\n\
00229 \n\
00230 float64 x\n\
00231 float64 y\n\
00232 float64 z\n\
00233 float64 w\n\
00234 \n\
00235 ================================================================================\n\
00236 MSG: sensor_msgs/PointCloud\n\
00237 # This message holds a collection of 3d points, plus optional additional\n\
00238 # information about each point.\n\
00239 \n\
00240 # Time of sensor data acquisition, coordinate frame ID.\n\
00241 Header header\n\
00242 \n\
00243 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00244 # in the frame given in the header.\n\
00245 geometry_msgs/Point32[] points\n\
00246 \n\
00247 # Each channel should have the same number of elements as points array,\n\
00248 # and the data in each channel should correspond 1:1 with each point.\n\
00249 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00250 ChannelFloat32[] channels\n\
00251 \n\
00252 ================================================================================\n\
00253 MSG: geometry_msgs/Point32\n\
00254 # This contains the position of a point in free space(with 32 bits of precision).\n\
00255 # It is recommeded to use Point wherever possible instead of Point32. \n\
00256 # \n\
00257 # This recommendation is to promote interoperability. \n\
00258 #\n\
00259 # This message is designed to take up less space when sending\n\
00260 # lots of points at once, as in the case of a PointCloud. \n\
00261 \n\
00262 float32 x\n\
00263 float32 y\n\
00264 float32 z\n\
00265 ================================================================================\n\
00266 MSG: sensor_msgs/ChannelFloat32\n\
00267 # This message is used by the PointCloud message to hold optional data\n\
00268 # associated with each point in the cloud. The length of the values\n\
00269 # array should be the same as the length of the points array in the\n\
00270 # PointCloud, and each value should be associated with the corresponding\n\
00271 # point.\n\
00272 \n\
00273 # Channel names in existing practice include:\n\
00274 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00275 # This is opposite to usual conventions but remains for\n\
00276 # historical reasons. The newer PointCloud2 message has no\n\
00277 # such problem.\n\
00278 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00279 # (R,G,B) values packed into the least significant 24 bits,\n\
00280 # in order.\n\
00281 # \"intensity\" - laser or pixel intensity.\n\
00282 # \"distance\"\n\
00283 \n\
00284 # The channel name should give semantics of the channel (e.g.\n\
00285 # \"intensity\" instead of \"value\").\n\
00286 string name\n\
00287 \n\
00288 # The values array should be 1-1 with the elements of the associated\n\
00289 # PointCloud.\n\
00290 float32[] values\n\
00291 \n\
00292 "; }
00293 public:
00294 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00295
00296 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00297
00298 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00299 {
00300 ros::serialization::OStream stream(write_ptr, 1000000000);
00301 ros::serialization::serialize(stream, table);
00302 ros::serialization::serialize(stream, clusters);
00303 ros::serialization::serialize(stream, result);
00304 return stream.getData();
00305 }
00306
00307 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00308 {
00309 ros::serialization::IStream stream(read_ptr, 1000000000);
00310 ros::serialization::deserialize(stream, table);
00311 ros::serialization::deserialize(stream, clusters);
00312 ros::serialization::deserialize(stream, result);
00313 return stream.getData();
00314 }
00315
00316 ROS_DEPRECATED virtual uint32_t serializationLength() const
00317 {
00318 uint32_t size = 0;
00319 size += ros::serialization::serializationLength(table);
00320 size += ros::serialization::serializationLength(clusters);
00321 size += ros::serialization::serializationLength(result);
00322 return size;
00323 }
00324
00325 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > Ptr;
00326 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> const> ConstPtr;
00327 };
00328 typedef ::tabletop_object_detector::TabletopSegmentationResponse_<std::allocator<void> > TabletopSegmentationResponse;
00329
00330 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse> TabletopSegmentationResponsePtr;
00331 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse const> TabletopSegmentationResponseConstPtr;
00332
00333 struct TabletopSegmentation
00334 {
00335
00336 typedef TabletopSegmentationRequest Request;
00337 typedef TabletopSegmentationResponse Response;
00338 Request request;
00339 Response response;
00340
00341 typedef Request RequestType;
00342 typedef Response ResponseType;
00343 };
00344 }
00345
00346 namespace ros
00347 {
00348 namespace message_traits
00349 {
00350 template<class ContainerAllocator>
00351 struct MD5Sum< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00352 static const char* value()
00353 {
00354 return "d41d8cd98f00b204e9800998ecf8427e";
00355 }
00356
00357 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00358 static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL;
00359 static const uint64_t static_value2 = 0xe9800998ecf8427eULL;
00360 };
00361
00362 template<class ContainerAllocator>
00363 struct DataType< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00364 static const char* value()
00365 {
00366 return "tabletop_object_detector/TabletopSegmentationRequest";
00367 }
00368
00369 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00370 };
00371
00372 template<class ContainerAllocator>
00373 struct Definition< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00374 static const char* value()
00375 {
00376 return "\n\
00377 \n\
00378 \n\
00379 ";
00380 }
00381
00382 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00383 };
00384
00385 template<class ContainerAllocator> struct IsFixedSize< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > : public TrueType {};
00386 }
00387 }
00388
00389
00390 namespace ros
00391 {
00392 namespace message_traits
00393 {
00394 template<class ContainerAllocator>
00395 struct MD5Sum< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00396 static const char* value()
00397 {
00398 return "4e3320ac33e6de7047804c8f0f76efd0";
00399 }
00400
00401 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00402 static const uint64_t static_value1 = 0x4e3320ac33e6de70ULL;
00403 static const uint64_t static_value2 = 0x47804c8f0f76efd0ULL;
00404 };
00405
00406 template<class ContainerAllocator>
00407 struct DataType< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00408 static const char* value()
00409 {
00410 return "tabletop_object_detector/TabletopSegmentationResponse";
00411 }
00412
00413 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00414 };
00415
00416 template<class ContainerAllocator>
00417 struct Definition< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00418 static const char* value()
00419 {
00420 return "\n\
00421 \n\
00422 Table table\n\
00423 \n\
00424 \n\
00425 sensor_msgs/PointCloud[] clusters\n\
00426 \n\
00427 \n\
00428 int32 NO_CLOUD_RECEIVED = 1\n\
00429 int32 NO_TABLE = 2\n\
00430 int32 OTHER_ERROR = 3\n\
00431 int32 SUCCESS = 4\n\
00432 int32 result\n\
00433 \n\
00434 \n\
00435 ================================================================================\n\
00436 MSG: tabletop_object_detector/Table\n\
00437 # Informs that a planar table has been detected at a given location\n\
00438 \n\
00439 # The pose gives you the transform that take you to the coordinate system\n\
00440 # of the table, with the origin somewhere in the table plane and the \n\
00441 # z axis normal to the plane\n\
00442 geometry_msgs/PoseStamped pose\n\
00443 \n\
00444 # These values give you the observed extents of the table, along x and y,\n\
00445 # in the table's own coordinate system (above)\n\
00446 # there is no guarantee that the origin of the table coordinate system is\n\
00447 # inside the boundary defined by these values. \n\
00448 float32 x_min\n\
00449 float32 x_max\n\
00450 float32 y_min\n\
00451 float32 y_max\n\
00452 \n\
00453 # There is no guarantee that the table doe NOT extend further than these \n\
00454 # values; this is just as far as we've observed it.\n\
00455 \n\
00456 ================================================================================\n\
00457 MSG: geometry_msgs/PoseStamped\n\
00458 # A Pose with reference coordinate frame and timestamp\n\
00459 Header header\n\
00460 Pose pose\n\
00461 \n\
00462 ================================================================================\n\
00463 MSG: std_msgs/Header\n\
00464 # Standard metadata for higher-level stamped data types.\n\
00465 # This is generally used to communicate timestamped data \n\
00466 # in a particular coordinate frame.\n\
00467 # \n\
00468 # sequence ID: consecutively increasing ID \n\
00469 uint32 seq\n\
00470 #Two-integer timestamp that is expressed as:\n\
00471 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00472 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00473 # time-handling sugar is provided by the client library\n\
00474 time stamp\n\
00475 #Frame this data is associated with\n\
00476 # 0: no frame\n\
00477 # 1: global frame\n\
00478 string frame_id\n\
00479 \n\
00480 ================================================================================\n\
00481 MSG: geometry_msgs/Pose\n\
00482 # A representation of pose in free space, composed of postion and orientation. \n\
00483 Point position\n\
00484 Quaternion orientation\n\
00485 \n\
00486 ================================================================================\n\
00487 MSG: geometry_msgs/Point\n\
00488 # This contains the position of a point in free space\n\
00489 float64 x\n\
00490 float64 y\n\
00491 float64 z\n\
00492 \n\
00493 ================================================================================\n\
00494 MSG: geometry_msgs/Quaternion\n\
00495 # This represents an orientation in free space in quaternion form.\n\
00496 \n\
00497 float64 x\n\
00498 float64 y\n\
00499 float64 z\n\
00500 float64 w\n\
00501 \n\
00502 ================================================================================\n\
00503 MSG: sensor_msgs/PointCloud\n\
00504 # This message holds a collection of 3d points, plus optional additional\n\
00505 # information about each point.\n\
00506 \n\
00507 # Time of sensor data acquisition, coordinate frame ID.\n\
00508 Header header\n\
00509 \n\
00510 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00511 # in the frame given in the header.\n\
00512 geometry_msgs/Point32[] points\n\
00513 \n\
00514 # Each channel should have the same number of elements as points array,\n\
00515 # and the data in each channel should correspond 1:1 with each point.\n\
00516 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00517 ChannelFloat32[] channels\n\
00518 \n\
00519 ================================================================================\n\
00520 MSG: geometry_msgs/Point32\n\
00521 # This contains the position of a point in free space(with 32 bits of precision).\n\
00522 # It is recommeded to use Point wherever possible instead of Point32. \n\
00523 # \n\
00524 # This recommendation is to promote interoperability. \n\
00525 #\n\
00526 # This message is designed to take up less space when sending\n\
00527 # lots of points at once, as in the case of a PointCloud. \n\
00528 \n\
00529 float32 x\n\
00530 float32 y\n\
00531 float32 z\n\
00532 ================================================================================\n\
00533 MSG: sensor_msgs/ChannelFloat32\n\
00534 # This message is used by the PointCloud message to hold optional data\n\
00535 # associated with each point in the cloud. The length of the values\n\
00536 # array should be the same as the length of the points array in the\n\
00537 # PointCloud, and each value should be associated with the corresponding\n\
00538 # point.\n\
00539 \n\
00540 # Channel names in existing practice include:\n\
00541 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00542 # This is opposite to usual conventions but remains for\n\
00543 # historical reasons. The newer PointCloud2 message has no\n\
00544 # such problem.\n\
00545 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00546 # (R,G,B) values packed into the least significant 24 bits,\n\
00547 # in order.\n\
00548 # \"intensity\" - laser or pixel intensity.\n\
00549 # \"distance\"\n\
00550 \n\
00551 # The channel name should give semantics of the channel (e.g.\n\
00552 # \"intensity\" instead of \"value\").\n\
00553 string name\n\
00554 \n\
00555 # The values array should be 1-1 with the elements of the associated\n\
00556 # PointCloud.\n\
00557 float32[] values\n\
00558 \n\
00559 ";
00560 }
00561
00562 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00563 };
00564
00565 }
00566 }
00567
00568 namespace ros
00569 {
00570 namespace serialization
00571 {
00572
00573 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> >
00574 {
00575 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00576 {
00577 }
00578
00579 ROS_DECLARE_ALLINONE_SERIALIZER;
00580 };
00581 }
00582 }
00583
00584
00585 namespace ros
00586 {
00587 namespace serialization
00588 {
00589
00590 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> >
00591 {
00592 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00593 {
00594 stream.next(m.table);
00595 stream.next(m.clusters);
00596 stream.next(m.result);
00597 }
00598
00599 ROS_DECLARE_ALLINONE_SERIALIZER;
00600 };
00601 }
00602 }
00603
00604 namespace ros
00605 {
00606 namespace service_traits
00607 {
00608 template<>
00609 struct MD5Sum<tabletop_object_detector::TabletopSegmentation> {
00610 static const char* value()
00611 {
00612 return "4e3320ac33e6de7047804c8f0f76efd0";
00613 }
00614
00615 static const char* value(const tabletop_object_detector::TabletopSegmentation&) { return value(); }
00616 };
00617
00618 template<>
00619 struct DataType<tabletop_object_detector::TabletopSegmentation> {
00620 static const char* value()
00621 {
00622 return "tabletop_object_detector/TabletopSegmentation";
00623 }
00624
00625 static const char* value(const tabletop_object_detector::TabletopSegmentation&) { return value(); }
00626 };
00627
00628 template<class ContainerAllocator>
00629 struct MD5Sum<tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00630 static const char* value()
00631 {
00632 return "4e3320ac33e6de7047804c8f0f76efd0";
00633 }
00634
00635 static const char* value(const tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00636 };
00637
00638 template<class ContainerAllocator>
00639 struct DataType<tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00640 static const char* value()
00641 {
00642 return "tabletop_object_detector/TabletopSegmentation";
00643 }
00644
00645 static const char* value(const tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00646 };
00647
00648 template<class ContainerAllocator>
00649 struct MD5Sum<tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00650 static const char* value()
00651 {
00652 return "4e3320ac33e6de7047804c8f0f76efd0";
00653 }
00654
00655 static const char* value(const tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00656 };
00657
00658 template<class ContainerAllocator>
00659 struct DataType<tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00660 static const char* value()
00661 {
00662 return "tabletop_object_detector/TabletopSegmentation";
00663 }
00664
00665 static const char* value(const tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00666 };
00667
00668 }
00669 }
00670
00671 #endif // TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPSEGMENTATION_H
00672