00001
00002 #ifndef WORLDMODEL_MSGS_MESSAGE_OBJECT_H
00003 #define WORLDMODEL_MSGS_MESSAGE_OBJECT_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 "std_msgs/Header.h"
00018 #include "geometry_msgs/PoseWithCovariance.h"
00019 #include "worldmodel_msgs/ObjectInfo.h"
00020 #include "worldmodel_msgs/ObjectState.h"
00021
00022 namespace worldmodel_msgs
00023 {
00024 template <class ContainerAllocator>
00025 struct Object_ {
00026 typedef Object_<ContainerAllocator> Type;
00027
00028 Object_()
00029 : header()
00030 , pose()
00031 , info()
00032 , state()
00033 {
00034 }
00035
00036 Object_(const ContainerAllocator& _alloc)
00037 : header(_alloc)
00038 , pose(_alloc)
00039 , info(_alloc)
00040 , state(_alloc)
00041 {
00042 }
00043
00044 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00045 ::std_msgs::Header_<ContainerAllocator> header;
00046
00047 typedef ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> _pose_type;
00048 ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> pose;
00049
00050 typedef ::worldmodel_msgs::ObjectInfo_<ContainerAllocator> _info_type;
00051 ::worldmodel_msgs::ObjectInfo_<ContainerAllocator> info;
00052
00053 typedef ::worldmodel_msgs::ObjectState_<ContainerAllocator> _state_type;
00054 ::worldmodel_msgs::ObjectState_<ContainerAllocator> state;
00055
00056
00057 private:
00058 static const char* __s_getDataType_() { return "worldmodel_msgs/Object"; }
00059 public:
00060 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00061
00062 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00063
00064 private:
00065 static const char* __s_getMD5Sum_() { return "bc2b29ddef39c215dc87ef727bf53447"; }
00066 public:
00067 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00068
00069 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00070
00071 private:
00072 static const char* __s_getMessageDefinition_() { return "# This message represents an estimate of an object's pose and identity.\n\
00073 \n\
00074 # The header.\n\
00075 # stamp: Timestamp of last update.\n\
00076 # frame_id: Coordinate frame, in which the pose is given\n\
00077 Header header\n\
00078 \n\
00079 # The pose\n\
00080 geometry_msgs/PoseWithCovariance pose\n\
00081 \n\
00082 # Further information about the object\n\
00083 ObjectInfo info\n\
00084 \n\
00085 # The tracked state of the object\n\
00086 ObjectState state\n\
00087 \n\
00088 ================================================================================\n\
00089 MSG: std_msgs/Header\n\
00090 # Standard metadata for higher-level stamped data types.\n\
00091 # This is generally used to communicate timestamped data \n\
00092 # in a particular coordinate frame.\n\
00093 # \n\
00094 # sequence ID: consecutively increasing ID \n\
00095 uint32 seq\n\
00096 #Two-integer timestamp that is expressed as:\n\
00097 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00098 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00099 # time-handling sugar is provided by the client library\n\
00100 time stamp\n\
00101 #Frame this data is associated with\n\
00102 # 0: no frame\n\
00103 # 1: global frame\n\
00104 string frame_id\n\
00105 \n\
00106 ================================================================================\n\
00107 MSG: geometry_msgs/PoseWithCovariance\n\
00108 # This represents a pose in free space with uncertainty.\n\
00109 \n\
00110 Pose pose\n\
00111 \n\
00112 # Row-major representation of the 6x6 covariance matrix\n\
00113 # The orientation parameters use a fixed-axis representation.\n\
00114 # In order, the parameters are:\n\
00115 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00116 float64[36] covariance\n\
00117 \n\
00118 ================================================================================\n\
00119 MSG: geometry_msgs/Pose\n\
00120 # A representation of pose in free space, composed of postion and orientation. \n\
00121 Point position\n\
00122 Quaternion orientation\n\
00123 \n\
00124 ================================================================================\n\
00125 MSG: geometry_msgs/Point\n\
00126 # This contains the position of a point in free space\n\
00127 float64 x\n\
00128 float64 y\n\
00129 float64 z\n\
00130 \n\
00131 ================================================================================\n\
00132 MSG: geometry_msgs/Quaternion\n\
00133 # This represents an orientation in free space in quaternion form.\n\
00134 \n\
00135 float64 x\n\
00136 float64 y\n\
00137 float64 z\n\
00138 float64 w\n\
00139 \n\
00140 ================================================================================\n\
00141 MSG: worldmodel_msgs/ObjectInfo\n\
00142 # This message contains information about the estimated class affiliation, object id and corresponding support\n\
00143 \n\
00144 # A string identifying the object's class (all objects of a class look the same)\n\
00145 string class_id\n\
00146 \n\
00147 # A string identifying the specific object\n\
00148 string object_id\n\
00149 \n\
00150 # A string that contains the name or a description of the specific object\n\
00151 string name\n\
00152 \n\
00153 # The support (degree of belief) of the object's presence given as log odd ratio\n\
00154 float32 support\n\
00155 \n\
00156 \n\
00157 ================================================================================\n\
00158 MSG: worldmodel_msgs/ObjectState\n\
00159 # The state of an object estimate used to track\n\
00160 # states smaller than 0 disable all updates\n\
00161 \n\
00162 int8 UNKNOWN = 0\n\
00163 int8 PENDING = 1\n\
00164 int8 ACTIVE = 2\n\
00165 int8 CONFIRMED = -1\n\
00166 int8 DISCARDED = -2\n\
00167 int8 APPROACHING = -3\n\
00168 \n\
00169 int8 state\n\
00170 \n\
00171 "; }
00172 public:
00173 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00174
00175 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00176
00177 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00178 {
00179 ros::serialization::OStream stream(write_ptr, 1000000000);
00180 ros::serialization::serialize(stream, header);
00181 ros::serialization::serialize(stream, pose);
00182 ros::serialization::serialize(stream, info);
00183 ros::serialization::serialize(stream, state);
00184 return stream.getData();
00185 }
00186
00187 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00188 {
00189 ros::serialization::IStream stream(read_ptr, 1000000000);
00190 ros::serialization::deserialize(stream, header);
00191 ros::serialization::deserialize(stream, pose);
00192 ros::serialization::deserialize(stream, info);
00193 ros::serialization::deserialize(stream, state);
00194 return stream.getData();
00195 }
00196
00197 ROS_DEPRECATED virtual uint32_t serializationLength() const
00198 {
00199 uint32_t size = 0;
00200 size += ros::serialization::serializationLength(header);
00201 size += ros::serialization::serializationLength(pose);
00202 size += ros::serialization::serializationLength(info);
00203 size += ros::serialization::serializationLength(state);
00204 return size;
00205 }
00206
00207 typedef boost::shared_ptr< ::worldmodel_msgs::Object_<ContainerAllocator> > Ptr;
00208 typedef boost::shared_ptr< ::worldmodel_msgs::Object_<ContainerAllocator> const> ConstPtr;
00209 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00210 };
00211 typedef ::worldmodel_msgs::Object_<std::allocator<void> > Object;
00212
00213 typedef boost::shared_ptr< ::worldmodel_msgs::Object> ObjectPtr;
00214 typedef boost::shared_ptr< ::worldmodel_msgs::Object const> ObjectConstPtr;
00215
00216
00217 template<typename ContainerAllocator>
00218 std::ostream& operator<<(std::ostream& s, const ::worldmodel_msgs::Object_<ContainerAllocator> & v)
00219 {
00220 ros::message_operations::Printer< ::worldmodel_msgs::Object_<ContainerAllocator> >::stream(s, "", v);
00221 return s;}
00222
00223 }
00224
00225 namespace ros
00226 {
00227 namespace message_traits
00228 {
00229 template<class ContainerAllocator> struct IsMessage< ::worldmodel_msgs::Object_<ContainerAllocator> > : public TrueType {};
00230 template<class ContainerAllocator> struct IsMessage< ::worldmodel_msgs::Object_<ContainerAllocator> const> : public TrueType {};
00231 template<class ContainerAllocator>
00232 struct MD5Sum< ::worldmodel_msgs::Object_<ContainerAllocator> > {
00233 static const char* value()
00234 {
00235 return "bc2b29ddef39c215dc87ef727bf53447";
00236 }
00237
00238 static const char* value(const ::worldmodel_msgs::Object_<ContainerAllocator> &) { return value(); }
00239 static const uint64_t static_value1 = 0xbc2b29ddef39c215ULL;
00240 static const uint64_t static_value2 = 0xdc87ef727bf53447ULL;
00241 };
00242
00243 template<class ContainerAllocator>
00244 struct DataType< ::worldmodel_msgs::Object_<ContainerAllocator> > {
00245 static const char* value()
00246 {
00247 return "worldmodel_msgs/Object";
00248 }
00249
00250 static const char* value(const ::worldmodel_msgs::Object_<ContainerAllocator> &) { return value(); }
00251 };
00252
00253 template<class ContainerAllocator>
00254 struct Definition< ::worldmodel_msgs::Object_<ContainerAllocator> > {
00255 static const char* value()
00256 {
00257 return "# This message represents an estimate of an object's pose and identity.\n\
00258 \n\
00259 # The header.\n\
00260 # stamp: Timestamp of last update.\n\
00261 # frame_id: Coordinate frame, in which the pose is given\n\
00262 Header header\n\
00263 \n\
00264 # The pose\n\
00265 geometry_msgs/PoseWithCovariance pose\n\
00266 \n\
00267 # Further information about the object\n\
00268 ObjectInfo info\n\
00269 \n\
00270 # The tracked state of the object\n\
00271 ObjectState state\n\
00272 \n\
00273 ================================================================================\n\
00274 MSG: std_msgs/Header\n\
00275 # Standard metadata for higher-level stamped data types.\n\
00276 # This is generally used to communicate timestamped data \n\
00277 # in a particular coordinate frame.\n\
00278 # \n\
00279 # sequence ID: consecutively increasing ID \n\
00280 uint32 seq\n\
00281 #Two-integer timestamp that is expressed as:\n\
00282 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00283 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00284 # time-handling sugar is provided by the client library\n\
00285 time stamp\n\
00286 #Frame this data is associated with\n\
00287 # 0: no frame\n\
00288 # 1: global frame\n\
00289 string frame_id\n\
00290 \n\
00291 ================================================================================\n\
00292 MSG: geometry_msgs/PoseWithCovariance\n\
00293 # This represents a pose in free space with uncertainty.\n\
00294 \n\
00295 Pose pose\n\
00296 \n\
00297 # Row-major representation of the 6x6 covariance matrix\n\
00298 # The orientation parameters use a fixed-axis representation.\n\
00299 # In order, the parameters are:\n\
00300 # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\
00301 float64[36] covariance\n\
00302 \n\
00303 ================================================================================\n\
00304 MSG: geometry_msgs/Pose\n\
00305 # A representation of pose in free space, composed of postion and orientation. \n\
00306 Point position\n\
00307 Quaternion orientation\n\
00308 \n\
00309 ================================================================================\n\
00310 MSG: geometry_msgs/Point\n\
00311 # This contains the position of a point in free space\n\
00312 float64 x\n\
00313 float64 y\n\
00314 float64 z\n\
00315 \n\
00316 ================================================================================\n\
00317 MSG: geometry_msgs/Quaternion\n\
00318 # This represents an orientation in free space in quaternion form.\n\
00319 \n\
00320 float64 x\n\
00321 float64 y\n\
00322 float64 z\n\
00323 float64 w\n\
00324 \n\
00325 ================================================================================\n\
00326 MSG: worldmodel_msgs/ObjectInfo\n\
00327 # This message contains information about the estimated class affiliation, object id and corresponding support\n\
00328 \n\
00329 # A string identifying the object's class (all objects of a class look the same)\n\
00330 string class_id\n\
00331 \n\
00332 # A string identifying the specific object\n\
00333 string object_id\n\
00334 \n\
00335 # A string that contains the name or a description of the specific object\n\
00336 string name\n\
00337 \n\
00338 # The support (degree of belief) of the object's presence given as log odd ratio\n\
00339 float32 support\n\
00340 \n\
00341 \n\
00342 ================================================================================\n\
00343 MSG: worldmodel_msgs/ObjectState\n\
00344 # The state of an object estimate used to track\n\
00345 # states smaller than 0 disable all updates\n\
00346 \n\
00347 int8 UNKNOWN = 0\n\
00348 int8 PENDING = 1\n\
00349 int8 ACTIVE = 2\n\
00350 int8 CONFIRMED = -1\n\
00351 int8 DISCARDED = -2\n\
00352 int8 APPROACHING = -3\n\
00353 \n\
00354 int8 state\n\
00355 \n\
00356 ";
00357 }
00358
00359 static const char* value(const ::worldmodel_msgs::Object_<ContainerAllocator> &) { return value(); }
00360 };
00361
00362 template<class ContainerAllocator> struct HasHeader< ::worldmodel_msgs::Object_<ContainerAllocator> > : public TrueType {};
00363 template<class ContainerAllocator> struct HasHeader< const ::worldmodel_msgs::Object_<ContainerAllocator> > : public TrueType {};
00364 }
00365 }
00366
00367 namespace ros
00368 {
00369 namespace serialization
00370 {
00371
00372 template<class ContainerAllocator> struct Serializer< ::worldmodel_msgs::Object_<ContainerAllocator> >
00373 {
00374 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00375 {
00376 stream.next(m.header);
00377 stream.next(m.pose);
00378 stream.next(m.info);
00379 stream.next(m.state);
00380 }
00381
00382 ROS_DECLARE_ALLINONE_SERIALIZER;
00383 };
00384 }
00385 }
00386
00387 namespace ros
00388 {
00389 namespace message_operations
00390 {
00391
00392 template<class ContainerAllocator>
00393 struct Printer< ::worldmodel_msgs::Object_<ContainerAllocator> >
00394 {
00395 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::worldmodel_msgs::Object_<ContainerAllocator> & v)
00396 {
00397 s << indent << "header: ";
00398 s << std::endl;
00399 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00400 s << indent << "pose: ";
00401 s << std::endl;
00402 Printer< ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> >::stream(s, indent + " ", v.pose);
00403 s << indent << "info: ";
00404 s << std::endl;
00405 Printer< ::worldmodel_msgs::ObjectInfo_<ContainerAllocator> >::stream(s, indent + " ", v.info);
00406 s << indent << "state: ";
00407 s << std::endl;
00408 Printer< ::worldmodel_msgs::ObjectState_<ContainerAllocator> >::stream(s, indent + " ", v.state);
00409 }
00410 };
00411
00412
00413 }
00414 }
00415
00416 #endif // WORLDMODEL_MSGS_MESSAGE_OBJECT_H
00417