00001
00002 #ifndef IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_H
00003 #define IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_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 "geometry_msgs/Point32.h"
00018 #include "geometry_msgs/Point32.h"
00019 #include "geometry_msgs/Point32.h"
00020 #include "sensor_msgs/PointCloud.h"
00021 #include "sensor_msgs/Image.h"
00022
00023 namespace ias_table_msgs
00024 {
00025 template <class ContainerAllocator>
00026 struct TableObject_ {
00027 typedef TableObject_<ContainerAllocator> Type;
00028
00029 TableObject_()
00030 : center()
00031 , min_bound()
00032 , max_bound()
00033 , object_cop_id(0)
00034 , lo_id(0)
00035 , points()
00036 , roi()
00037 , perception_method()
00038 , sensor_type()
00039 , object_type()
00040 , object_color()
00041 , object_geometric_type()
00042 , table_id(0)
00043 {
00044 }
00045
00046 TableObject_(const ContainerAllocator& _alloc)
00047 : center(_alloc)
00048 , min_bound(_alloc)
00049 , max_bound(_alloc)
00050 , object_cop_id(0)
00051 , lo_id(0)
00052 , points(_alloc)
00053 , roi(_alloc)
00054 , perception_method(_alloc)
00055 , sensor_type(_alloc)
00056 , object_type(_alloc)
00057 , object_color(_alloc)
00058 , object_geometric_type(_alloc)
00059 , table_id(0)
00060 {
00061 }
00062
00063 typedef ::geometry_msgs::Point32_<ContainerAllocator> _center_type;
00064 ::geometry_msgs::Point32_<ContainerAllocator> center;
00065
00066 typedef ::geometry_msgs::Point32_<ContainerAllocator> _min_bound_type;
00067 ::geometry_msgs::Point32_<ContainerAllocator> min_bound;
00068
00069 typedef ::geometry_msgs::Point32_<ContainerAllocator> _max_bound_type;
00070 ::geometry_msgs::Point32_<ContainerAllocator> max_bound;
00071
00072 typedef uint64_t _object_cop_id_type;
00073 uint64_t object_cop_id;
00074
00075 typedef uint64_t _lo_id_type;
00076 uint64_t lo_id;
00077
00078 typedef ::sensor_msgs::PointCloud_<ContainerAllocator> _points_type;
00079 ::sensor_msgs::PointCloud_<ContainerAllocator> points;
00080
00081 typedef ::sensor_msgs::Image_<ContainerAllocator> _roi_type;
00082 ::sensor_msgs::Image_<ContainerAllocator> roi;
00083
00084 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _perception_method_type;
00085 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > perception_method;
00086
00087 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _sensor_type_type;
00088 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > sensor_type;
00089
00090 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_type_type;
00091 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_type;
00092
00093 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_color_type;
00094 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_color;
00095
00096 typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > _object_geometric_type_type;
00097 std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > object_geometric_type;
00098
00099 typedef uint64_t _table_id_type;
00100 uint64_t table_id;
00101
00102
00103 typedef boost::shared_ptr< ::ias_table_msgs::TableObject_<ContainerAllocator> > Ptr;
00104 typedef boost::shared_ptr< ::ias_table_msgs::TableObject_<ContainerAllocator> const> ConstPtr;
00105 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00106 };
00107 typedef ::ias_table_msgs::TableObject_<std::allocator<void> > TableObject;
00108
00109 typedef boost::shared_ptr< ::ias_table_msgs::TableObject> TableObjectPtr;
00110 typedef boost::shared_ptr< ::ias_table_msgs::TableObject const> TableObjectConstPtr;
00111
00112
00113 template<typename ContainerAllocator>
00114 std::ostream& operator<<(std::ostream& s, const ::ias_table_msgs::TableObject_<ContainerAllocator> & v)
00115 {
00116 ros::message_operations::Printer< ::ias_table_msgs::TableObject_<ContainerAllocator> >::stream(s, "", v);
00117 return s;}
00118
00119 }
00120
00121 namespace ros
00122 {
00123 namespace message_traits
00124 {
00125 template<class ContainerAllocator> struct IsMessage< ::ias_table_msgs::TableObject_<ContainerAllocator> > : public TrueType {};
00126 template<class ContainerAllocator> struct IsMessage< ::ias_table_msgs::TableObject_<ContainerAllocator> const> : public TrueType {};
00127 template<class ContainerAllocator>
00128 struct MD5Sum< ::ias_table_msgs::TableObject_<ContainerAllocator> > {
00129 static const char* value()
00130 {
00131 return "3ce72124397384b196976e00d07c3482";
00132 }
00133
00134 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); }
00135 static const uint64_t static_value1 = 0x3ce72124397384b1ULL;
00136 static const uint64_t static_value2 = 0x96976e00d07c3482ULL;
00137 };
00138
00139 template<class ContainerAllocator>
00140 struct DataType< ::ias_table_msgs::TableObject_<ContainerAllocator> > {
00141 static const char* value()
00142 {
00143 return "ias_table_msgs/TableObject";
00144 }
00145
00146 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); }
00147 };
00148
00149 template<class ContainerAllocator>
00150 struct Definition< ::ias_table_msgs::TableObject_<ContainerAllocator> > {
00151 static const char* value()
00152 {
00153 return "geometry_msgs/Point32 center\n\
00154 geometry_msgs/Point32 min_bound\n\
00155 geometry_msgs/Point32 max_bound\n\
00156 \n\
00157 uint64 object_cop_id\n\
00158 uint64 lo_id\n\
00159 \n\
00160 sensor_msgs/PointCloud points\n\
00161 sensor_msgs/Image roi\n\
00162 \n\
00163 string perception_method\n\
00164 string sensor_type\n\
00165 string object_type\n\
00166 string object_color\n\
00167 string object_geometric_type\n\
00168 uint64 table_id\n\
00169 \n\
00170 ================================================================================\n\
00171 MSG: geometry_msgs/Point32\n\
00172 # This contains the position of a point in free space(with 32 bits of precision).\n\
00173 # It is recommeded to use Point wherever possible instead of Point32. \n\
00174 # \n\
00175 # This recommendation is to promote interoperability. \n\
00176 #\n\
00177 # This message is designed to take up less space when sending\n\
00178 # lots of points at once, as in the case of a PointCloud. \n\
00179 \n\
00180 float32 x\n\
00181 float32 y\n\
00182 float32 z\n\
00183 ================================================================================\n\
00184 MSG: sensor_msgs/PointCloud\n\
00185 # This message holds a collection of 3d points, plus optional additional\n\
00186 # information about each point.\n\
00187 \n\
00188 # Time of sensor data acquisition, coordinate frame ID.\n\
00189 Header header\n\
00190 \n\
00191 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
00192 # in the frame given in the header.\n\
00193 geometry_msgs/Point32[] points\n\
00194 \n\
00195 # Each channel should have the same number of elements as points array,\n\
00196 # and the data in each channel should correspond 1:1 with each point.\n\
00197 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
00198 ChannelFloat32[] channels\n\
00199 \n\
00200 ================================================================================\n\
00201 MSG: std_msgs/Header\n\
00202 # Standard metadata for higher-level stamped data types.\n\
00203 # This is generally used to communicate timestamped data \n\
00204 # in a particular coordinate frame.\n\
00205 # \n\
00206 # sequence ID: consecutively increasing ID \n\
00207 uint32 seq\n\
00208 #Two-integer timestamp that is expressed as:\n\
00209 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00210 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00211 # time-handling sugar is provided by the client library\n\
00212 time stamp\n\
00213 #Frame this data is associated with\n\
00214 # 0: no frame\n\
00215 # 1: global frame\n\
00216 string frame_id\n\
00217 \n\
00218 ================================================================================\n\
00219 MSG: sensor_msgs/ChannelFloat32\n\
00220 # This message is used by the PointCloud message to hold optional data\n\
00221 # associated with each point in the cloud. The length of the values\n\
00222 # array should be the same as the length of the points array in the\n\
00223 # PointCloud, and each value should be associated with the corresponding\n\
00224 # point.\n\
00225 \n\
00226 # Channel names in existing practice include:\n\
00227 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
00228 # This is opposite to usual conventions but remains for\n\
00229 # historical reasons. The newer PointCloud2 message has no\n\
00230 # such problem.\n\
00231 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
00232 # (R,G,B) values packed into the least significant 24 bits,\n\
00233 # in order.\n\
00234 # \"intensity\" - laser or pixel intensity.\n\
00235 # \"distance\"\n\
00236 \n\
00237 # The channel name should give semantics of the channel (e.g.\n\
00238 # \"intensity\" instead of \"value\").\n\
00239 string name\n\
00240 \n\
00241 # The values array should be 1-1 with the elements of the associated\n\
00242 # PointCloud.\n\
00243 float32[] values\n\
00244 \n\
00245 ================================================================================\n\
00246 MSG: sensor_msgs/Image\n\
00247 # This message contains an uncompressed image\n\
00248 # (0, 0) is at top-left corner of image\n\
00249 #\n\
00250 \n\
00251 Header header # Header timestamp should be acquisition time of image\n\
00252 # Header frame_id should be optical frame of camera\n\
00253 # origin of frame should be optical center of cameara\n\
00254 # +x should point to the right in the image\n\
00255 # +y should point down in the image\n\
00256 # +z should point into to plane of the image\n\
00257 # If the frame_id here and the frame_id of the CameraInfo\n\
00258 # message associated with the image conflict\n\
00259 # the behavior is undefined\n\
00260 \n\
00261 uint32 height # image height, that is, number of rows\n\
00262 uint32 width # image width, that is, number of columns\n\
00263 \n\
00264 # The legal values for encoding are in file src/image_encodings.cpp\n\
00265 # If you want to standardize a new string format, join\n\
00266 # ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\
00267 \n\
00268 string encoding # Encoding of pixels -- channel meaning, ordering, size\n\
00269 # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\
00270 \n\
00271 uint8 is_bigendian # is this data bigendian?\n\
00272 uint32 step # Full row length in bytes\n\
00273 uint8[] data # actual matrix data, size is (step * rows)\n\
00274 \n\
00275 ";
00276 }
00277
00278 static const char* value(const ::ias_table_msgs::TableObject_<ContainerAllocator> &) { return value(); }
00279 };
00280
00281 }
00282 }
00283
00284 namespace ros
00285 {
00286 namespace serialization
00287 {
00288
00289 template<class ContainerAllocator> struct Serializer< ::ias_table_msgs::TableObject_<ContainerAllocator> >
00290 {
00291 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00292 {
00293 stream.next(m.center);
00294 stream.next(m.min_bound);
00295 stream.next(m.max_bound);
00296 stream.next(m.object_cop_id);
00297 stream.next(m.lo_id);
00298 stream.next(m.points);
00299 stream.next(m.roi);
00300 stream.next(m.perception_method);
00301 stream.next(m.sensor_type);
00302 stream.next(m.object_type);
00303 stream.next(m.object_color);
00304 stream.next(m.object_geometric_type);
00305 stream.next(m.table_id);
00306 }
00307
00308 ROS_DECLARE_ALLINONE_SERIALIZER;
00309 };
00310 }
00311 }
00312
00313 namespace ros
00314 {
00315 namespace message_operations
00316 {
00317
00318 template<class ContainerAllocator>
00319 struct Printer< ::ias_table_msgs::TableObject_<ContainerAllocator> >
00320 {
00321 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::ias_table_msgs::TableObject_<ContainerAllocator> & v)
00322 {
00323 s << indent << "center: ";
00324 s << std::endl;
00325 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.center);
00326 s << indent << "min_bound: ";
00327 s << std::endl;
00328 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.min_bound);
00329 s << indent << "max_bound: ";
00330 s << std::endl;
00331 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.max_bound);
00332 s << indent << "object_cop_id: ";
00333 Printer<uint64_t>::stream(s, indent + " ", v.object_cop_id);
00334 s << indent << "lo_id: ";
00335 Printer<uint64_t>::stream(s, indent + " ", v.lo_id);
00336 s << indent << "points: ";
00337 s << std::endl;
00338 Printer< ::sensor_msgs::PointCloud_<ContainerAllocator> >::stream(s, indent + " ", v.points);
00339 s << indent << "roi: ";
00340 s << std::endl;
00341 Printer< ::sensor_msgs::Image_<ContainerAllocator> >::stream(s, indent + " ", v.roi);
00342 s << indent << "perception_method: ";
00343 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.perception_method);
00344 s << indent << "sensor_type: ";
00345 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.sensor_type);
00346 s << indent << "object_type: ";
00347 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_type);
00348 s << indent << "object_color: ";
00349 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_color);
00350 s << indent << "object_geometric_type: ";
00351 Printer<std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > >::stream(s, indent + " ", v.object_geometric_type);
00352 s << indent << "table_id: ";
00353 Printer<uint64_t>::stream(s, indent + " ", v.table_id);
00354 }
00355 };
00356
00357
00358 }
00359 }
00360
00361 #endif // IAS_TABLE_MSGS_MESSAGE_TABLEOBJECT_H
00362