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