Go to the documentation of this file.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 <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
00021
00022 #include "tabletop_object_detector/Table.h"
00023 #include "sensor_msgs/PointCloud.h"
00024
00025 namespace tabletop_object_detector
00026 {
00027 template <class ContainerAllocator>
00028 struct TabletopSegmentationRequest_ {
00029 typedef TabletopSegmentationRequest_<ContainerAllocator> Type;
00030
00031 TabletopSegmentationRequest_()
00032 : table()
00033 {
00034 }
00035
00036 TabletopSegmentationRequest_(const ContainerAllocator& _alloc)
00037 : table(_alloc)
00038 {
00039 }
00040
00041 typedef ::tabletop_object_detector::Table_<ContainerAllocator> _table_type;
00042 ::tabletop_object_detector::Table_<ContainerAllocator> table;
00043
00044
00045 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > Ptr;
00046 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> const> ConstPtr;
00047 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00048 };
00049 typedef ::tabletop_object_detector::TabletopSegmentationRequest_<std::allocator<void> > TabletopSegmentationRequest;
00050
00051 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest> TabletopSegmentationRequestPtr;
00052 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationRequest const> TabletopSegmentationRequestConstPtr;
00053
00054
00055
00056 template <class ContainerAllocator>
00057 struct TabletopSegmentationResponse_ {
00058 typedef TabletopSegmentationResponse_<ContainerAllocator> Type;
00059
00060 TabletopSegmentationResponse_()
00061 : table()
00062 , clusters()
00063 , result(0)
00064 {
00065 }
00066
00067 TabletopSegmentationResponse_(const ContainerAllocator& _alloc)
00068 : table(_alloc)
00069 , clusters(_alloc)
00070 , result(0)
00071 {
00072 }
00073
00074 typedef ::tabletop_object_detector::Table_<ContainerAllocator> _table_type;
00075 ::tabletop_object_detector::Table_<ContainerAllocator> table;
00076
00077 typedef std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > _clusters_type;
00078 std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > clusters;
00079
00080 typedef int32_t _result_type;
00081 int32_t result;
00082
00083 enum { NO_CLOUD_RECEIVED = 1 };
00084 enum { NO_TABLE = 2 };
00085 enum { OTHER_ERROR = 3 };
00086 enum { SUCCESS = 4 };
00087
00088 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > Ptr;
00089 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> const> ConstPtr;
00090 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00091 };
00092 typedef ::tabletop_object_detector::TabletopSegmentationResponse_<std::allocator<void> > TabletopSegmentationResponse;
00093
00094 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse> TabletopSegmentationResponsePtr;
00095 typedef boost::shared_ptr< ::tabletop_object_detector::TabletopSegmentationResponse const> TabletopSegmentationResponseConstPtr;
00096
00097
00098 struct TabletopSegmentation
00099 {
00100
00101 typedef TabletopSegmentationRequest Request;
00102 typedef TabletopSegmentationResponse Response;
00103 Request request;
00104 Response response;
00105
00106 typedef Request RequestType;
00107 typedef Response ResponseType;
00108 };
00109 }
00110
00111 namespace ros
00112 {
00113 namespace message_traits
00114 {
00115 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > : public TrueType {};
00116 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> const> : public TrueType {};
00117 template<class ContainerAllocator>
00118 struct MD5Sum< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00119 static const char* value()
00120 {
00121 return "2658053a5db85dc8883259fb888851ac";
00122 }
00123
00124 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00125 static const uint64_t static_value1 = 0x2658053a5db85dc8ULL;
00126 static const uint64_t static_value2 = 0x883259fb888851acULL;
00127 };
00128
00129 template<class ContainerAllocator>
00130 struct DataType< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00131 static const char* value()
00132 {
00133 return "tabletop_object_detector/TabletopSegmentationRequest";
00134 }
00135
00136 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00137 };
00138
00139 template<class ContainerAllocator>
00140 struct Definition< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00141 static const char* value()
00142 {
00143 return "\n\
00144 \n\
00145 \n\
00146 Table table\n\
00147 \n\
00148 \n\
00149 ================================================================================\n\
00150 MSG: tabletop_object_detector/Table\n\
00151 # Informs that a planar table has been detected at a given location\n\
00152 \n\
00153 # The pose gives you the transform that take you to the coordinate system\n\
00154 # of the table, with the origin somewhere in the table plane and the \n\
00155 # z axis normal to the plane\n\
00156 geometry_msgs/PoseStamped pose\n\
00157 \n\
00158 # These values give you the observed extents of the table, along x and y,\n\
00159 # in the table's own coordinate system (above)\n\
00160 # there is no guarantee that the origin of the table coordinate system is\n\
00161 # inside the boundary defined by these values. \n\
00162 float32 x_min\n\
00163 float32 x_max\n\
00164 float32 y_min\n\
00165 float32 y_max\n\
00166 \n\
00167 # There is no guarantee that the table does NOT extend further than these \n\
00168 # values; this is just as far as we've observed it.\n\
00169 \n\
00170 \n\
00171 # Newer table definition as triangle mesh of convex hull (relative to pose)\n\
00172 shape_msgs/Mesh convex_hull\n\
00173 \n\
00174 ================================================================================\n\
00175 MSG: geometry_msgs/PoseStamped\n\
00176 # A Pose with reference coordinate frame and timestamp\n\
00177 Header header\n\
00178 Pose pose\n\
00179 \n\
00180 ================================================================================\n\
00181 MSG: std_msgs/Header\n\
00182 # Standard metadata for higher-level stamped data types.\n\
00183 # This is generally used to communicate timestamped data \n\
00184 # in a particular coordinate frame.\n\
00185 # \n\
00186 # sequence ID: consecutively increasing ID \n\
00187 uint32 seq\n\
00188 #Two-integer timestamp that is expressed as:\n\
00189 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00190 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00191 # time-handling sugar is provided by the client library\n\
00192 time stamp\n\
00193 #Frame this data is associated with\n\
00194 # 0: no frame\n\
00195 # 1: global frame\n\
00196 string frame_id\n\
00197 \n\
00198 ================================================================================\n\
00199 MSG: geometry_msgs/Pose\n\
00200 # A representation of pose in free space, composed of postion and orientation. \n\
00201 Point position\n\
00202 Quaternion orientation\n\
00203 \n\
00204 ================================================================================\n\
00205 MSG: geometry_msgs/Point\n\
00206 # This contains the position of a point in free space\n\
00207 float64 x\n\
00208 float64 y\n\
00209 float64 z\n\
00210 \n\
00211 ================================================================================\n\
00212 MSG: geometry_msgs/Quaternion\n\
00213 # This represents an orientation in free space in quaternion form.\n\
00214 \n\
00215 float64 x\n\
00216 float64 y\n\
00217 float64 z\n\
00218 float64 w\n\
00219 \n\
00220 ================================================================================\n\
00221 MSG: shape_msgs/Mesh\n\
00222 # Definition of a mesh\n\
00223 \n\
00224 # list of triangles; the index values refer to positions in vertices[]\n\
00225 MeshTriangle[] triangles\n\
00226 \n\
00227 # the actual vertices that make up the mesh\n\
00228 geometry_msgs/Point[] vertices\n\
00229 \n\
00230 ================================================================================\n\
00231 MSG: shape_msgs/MeshTriangle\n\
00232 # Definition of a triangle's vertices\n\
00233 uint32[3] vertex_indices\n\
00234 \n\
00235 ";
00236 }
00237
00238 static const char* value(const ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00239 };
00240
00241 }
00242 }
00243
00244
00245 namespace ros
00246 {
00247 namespace message_traits
00248 {
00249 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > : public TrueType {};
00250 template<class ContainerAllocator> struct IsMessage< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> const> : public TrueType {};
00251 template<class ContainerAllocator>
00252 struct MD5Sum< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00253 static const char* value()
00254 {
00255 return "ca5ac826b9d0b968e01c52dfce13fecf";
00256 }
00257
00258 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00259 static const uint64_t static_value1 = 0xca5ac826b9d0b968ULL;
00260 static const uint64_t static_value2 = 0xe01c52dfce13fecfULL;
00261 };
00262
00263 template<class ContainerAllocator>
00264 struct DataType< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00265 static const char* value()
00266 {
00267 return "tabletop_object_detector/TabletopSegmentationResponse";
00268 }
00269
00270 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00271 };
00272
00273 template<class ContainerAllocator>
00274 struct Definition< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00275 static const char* value()
00276 {
00277 return "\n\
00278 \n\
00279 Table table\n\
00280 \n\
00281 \n\
00282 sensor_msgs/PointCloud[] clusters\n\
00283 \n\
00284 \n\
00285 int32 NO_CLOUD_RECEIVED = 1\n\
00286 int32 NO_TABLE = 2\n\
00287 int32 OTHER_ERROR = 3\n\
00288 int32 SUCCESS = 4\n\
00289 int32 result\n\
00290 \n\
00291 \n\
00292 ================================================================================\n\
00293 MSG: tabletop_object_detector/Table\n\
00294 # Informs that a planar table has been detected at a given location\n\
00295 \n\
00296 # The pose gives you the transform that take you to the coordinate system\n\
00297 # of the table, with the origin somewhere in the table plane and the \n\
00298 # z axis normal to the plane\n\
00299 geometry_msgs/PoseStamped pose\n\
00300 \n\
00301 # These values give you the observed extents of the table, along x and y,\n\
00302 # in the table's own coordinate system (above)\n\
00303 # there is no guarantee that the origin of the table coordinate system is\n\
00304 # inside the boundary defined by these values. \n\
00305 float32 x_min\n\
00306 float32 x_max\n\
00307 float32 y_min\n\
00308 float32 y_max\n\
00309 \n\
00310 # There is no guarantee that the table does NOT extend further than these \n\
00311 # values; this is just as far as we've observed it.\n\
00312 \n\
00313 \n\
00314 # Newer table definition as triangle mesh of convex hull (relative to pose)\n\
00315 shape_msgs/Mesh convex_hull\n\
00316 \n\
00317 ================================================================================\n\
00318 MSG: geometry_msgs/PoseStamped\n\
00319 # A Pose with reference coordinate frame and timestamp\n\
00320 Header header\n\
00321 Pose pose\n\
00322 \n\
00323 ================================================================================\n\
00324 MSG: std_msgs/Header\n\
00325 # Standard metadata for higher-level stamped data types.\n\
00326 # This is generally used to communicate timestamped data \n\
00327 # in a particular coordinate frame.\n\
00328 # \n\
00329 # sequence ID: consecutively increasing ID \n\
00330 uint32 seq\n\
00331 #Two-integer timestamp that is expressed as:\n\
00332 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00333 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00334 # time-handling sugar is provided by the client library\n\
00335 time stamp\n\
00336 #Frame this data is associated with\n\
00337 # 0: no frame\n\
00338 # 1: global frame\n\
00339 string frame_id\n\
00340 \n\
00341 ================================================================================\n\
00342 MSG: geometry_msgs/Pose\n\
00343 # A representation of pose in free space, composed of postion and orientation. \n\
00344 Point position\n\
00345 Quaternion orientation\n\
00346 \n\
00347 ================================================================================\n\
00348 MSG: geometry_msgs/Point\n\
00349 # This contains the position of a point in free space\n\
00350 float64 x\n\
00351 float64 y\n\
00352 float64 z\n\
00353 \n\
00354 ================================================================================\n\
00355 MSG: geometry_msgs/Quaternion\n\
00356 # This represents an orientation in free space in quaternion form.\n\
00357 \n\
00358 float64 x\n\
00359 float64 y\n\
00360 float64 z\n\
00361 float64 w\n\
00362 \n\
00363 ================================================================================\n\
00364 MSG: shape_msgs/Mesh\n\
00365 # Definition of a mesh\n\
00366 \n\
00367 # list of triangles; the index values refer to positions in vertices[]\n\
00368 MeshTriangle[] triangles\n\
00369 \n\
00370 # the actual vertices that make up the mesh\n\
00371 geometry_msgs/Point[] vertices\n\
00372 \n\
00373 ================================================================================\n\
00374 MSG: shape_msgs/MeshTriangle\n\
00375 # Definition of a triangle's vertices\n\
00376 uint32[3] vertex_indices\n\
00377 \n\
00378 ================================================================================\n\
00379 MSG: sensor_msgs/PointCloud\n\
00380 # This message holds a collection of 3d points, plus optional additional\n\
00381 # information about each point.\n\
00382 \n\
00383 # Time of sensor data acquisition, coordinate frame ID.\n\
00384 Header header\n\
00385 \n\
00386 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00387 # in the frame given in the header.\n\
00388 geometry_msgs/Point32[] points\n\
00389 \n\
00390 # Each channel should have the same number of elements as points array,\n\
00391 # and the data in each channel should correspond 1:1 with each point.\n\
00392 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00393 ChannelFloat32[] channels\n\
00394 \n\
00395 ================================================================================\n\
00396 MSG: geometry_msgs/Point32\n\
00397 # This contains the position of a point in free space(with 32 bits of precision).\n\
00398 # It is recommeded to use Point wherever possible instead of Point32. \n\
00399 # \n\
00400 # This recommendation is to promote interoperability. \n\
00401 #\n\
00402 # This message is designed to take up less space when sending\n\
00403 # lots of points at once, as in the case of a PointCloud. \n\
00404 \n\
00405 float32 x\n\
00406 float32 y\n\
00407 float32 z\n\
00408 ================================================================================\n\
00409 MSG: sensor_msgs/ChannelFloat32\n\
00410 # This message is used by the PointCloud message to hold optional data\n\
00411 # associated with each point in the cloud. The length of the values\n\
00412 # array should be the same as the length of the points array in the\n\
00413 # PointCloud, and each value should be associated with the corresponding\n\
00414 # point.\n\
00415 \n\
00416 # Channel names in existing practice include:\n\
00417 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00418 # This is opposite to usual conventions but remains for\n\
00419 # historical reasons. The newer PointCloud2 message has no\n\
00420 # such problem.\n\
00421 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00422 # (R,G,B) values packed into the least significant 24 bits,\n\
00423 # in order.\n\
00424 # \"intensity\" - laser or pixel intensity.\n\
00425 # \"distance\"\n\
00426 \n\
00427 # The channel name should give semantics of the channel (e.g.\n\
00428 # \"intensity\" instead of \"value\").\n\
00429 string name\n\
00430 \n\
00431 # The values array should be 1-1 with the elements of the associated\n\
00432 # PointCloud.\n\
00433 float32[] values\n\
00434 \n\
00435 ";
00436 }
00437
00438 static const char* value(const ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00439 };
00440
00441 }
00442 }
00443
00444 namespace ros
00445 {
00446 namespace serialization
00447 {
00448
00449 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> >
00450 {
00451 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00452 {
00453 stream.next(m.table);
00454 }
00455
00456 ROS_DECLARE_ALLINONE_SERIALIZER;
00457 };
00458 }
00459 }
00460
00461
00462 namespace ros
00463 {
00464 namespace serialization
00465 {
00466
00467 template<class ContainerAllocator> struct Serializer< ::tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> >
00468 {
00469 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00470 {
00471 stream.next(m.table);
00472 stream.next(m.clusters);
00473 stream.next(m.result);
00474 }
00475
00476 ROS_DECLARE_ALLINONE_SERIALIZER;
00477 };
00478 }
00479 }
00480
00481 namespace ros
00482 {
00483 namespace service_traits
00484 {
00485 template<>
00486 struct MD5Sum<tabletop_object_detector::TabletopSegmentation> {
00487 static const char* value()
00488 {
00489 return "27303108328e543c7f7da23443a40e01";
00490 }
00491
00492 static const char* value(const tabletop_object_detector::TabletopSegmentation&) { return value(); }
00493 };
00494
00495 template<>
00496 struct DataType<tabletop_object_detector::TabletopSegmentation> {
00497 static const char* value()
00498 {
00499 return "tabletop_object_detector/TabletopSegmentation";
00500 }
00501
00502 static const char* value(const tabletop_object_detector::TabletopSegmentation&) { return value(); }
00503 };
00504
00505 template<class ContainerAllocator>
00506 struct MD5Sum<tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00507 static const char* value()
00508 {
00509 return "27303108328e543c7f7da23443a40e01";
00510 }
00511
00512 static const char* value(const tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00513 };
00514
00515 template<class ContainerAllocator>
00516 struct DataType<tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> > {
00517 static const char* value()
00518 {
00519 return "tabletop_object_detector/TabletopSegmentation";
00520 }
00521
00522 static const char* value(const tabletop_object_detector::TabletopSegmentationRequest_<ContainerAllocator> &) { return value(); }
00523 };
00524
00525 template<class ContainerAllocator>
00526 struct MD5Sum<tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00527 static const char* value()
00528 {
00529 return "27303108328e543c7f7da23443a40e01";
00530 }
00531
00532 static const char* value(const tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00533 };
00534
00535 template<class ContainerAllocator>
00536 struct DataType<tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> > {
00537 static const char* value()
00538 {
00539 return "tabletop_object_detector/TabletopSegmentation";
00540 }
00541
00542 static const char* value(const tabletop_object_detector::TabletopSegmentationResponse_<ContainerAllocator> &) { return value(); }
00543 };
00544
00545 }
00546 }
00547
00548 #endif // TABLETOP_OBJECT_DETECTOR_SERVICE_TABLETOPSEGMENTATION_H
00549