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