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