00001
00002 #ifndef DOOR_MSGS_MESSAGE_DOOR_H
00003 #define DOOR_MSGS_MESSAGE_DOOR_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 "std_msgs/Header.h"
00014 #include "geometry_msgs/Point32.h"
00015 #include "geometry_msgs/Point32.h"
00016 #include "geometry_msgs/Point32.h"
00017 #include "geometry_msgs/Point32.h"
00018 #include "geometry_msgs/Point32.h"
00019 #include "geometry_msgs/Vector3.h"
00020
00021 namespace door_msgs
00022 {
00023 template <class ContainerAllocator>
00024 struct Door_ : public ros::Message
00025 {
00026 typedef Door_<ContainerAllocator> Type;
00027
00028 Door_()
00029 : header()
00030 , frame_p1()
00031 , frame_p2()
00032 , door_p1()
00033 , door_p2()
00034 , handle()
00035 , height(0.0)
00036 , hinge(0)
00037 , rot_dir(0)
00038 , latch_state(0)
00039 , travel_dir()
00040 , weight(0.0)
00041 {
00042 }
00043
00044 Door_(const ContainerAllocator& _alloc)
00045 : header(_alloc)
00046 , frame_p1(_alloc)
00047 , frame_p2(_alloc)
00048 , door_p1(_alloc)
00049 , door_p2(_alloc)
00050 , handle(_alloc)
00051 , height(0.0)
00052 , hinge(0)
00053 , rot_dir(0)
00054 , latch_state(0)
00055 , travel_dir(_alloc)
00056 , weight(0.0)
00057 {
00058 }
00059
00060 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00061 ::std_msgs::Header_<ContainerAllocator> header;
00062
00063 typedef ::geometry_msgs::Point32_<ContainerAllocator> _frame_p1_type;
00064 ::geometry_msgs::Point32_<ContainerAllocator> frame_p1;
00065
00066 typedef ::geometry_msgs::Point32_<ContainerAllocator> _frame_p2_type;
00067 ::geometry_msgs::Point32_<ContainerAllocator> frame_p2;
00068
00069 typedef ::geometry_msgs::Point32_<ContainerAllocator> _door_p1_type;
00070 ::geometry_msgs::Point32_<ContainerAllocator> door_p1;
00071
00072 typedef ::geometry_msgs::Point32_<ContainerAllocator> _door_p2_type;
00073 ::geometry_msgs::Point32_<ContainerAllocator> door_p2;
00074
00075 typedef ::geometry_msgs::Point32_<ContainerAllocator> _handle_type;
00076 ::geometry_msgs::Point32_<ContainerAllocator> handle;
00077
00078 typedef float _height_type;
00079 float height;
00080
00081 typedef int32_t _hinge_type;
00082 int32_t hinge;
00083
00084 typedef int32_t _rot_dir_type;
00085 int32_t rot_dir;
00086
00087 typedef int32_t _latch_state_type;
00088 int32_t latch_state;
00089
00090 typedef ::geometry_msgs::Vector3_<ContainerAllocator> _travel_dir_type;
00091 ::geometry_msgs::Vector3_<ContainerAllocator> travel_dir;
00092
00093 typedef float _weight_type;
00094 float weight;
00095
00096 enum { UNKNOWN = 0 };
00097 enum { HINGE_P1 = 1 };
00098 enum { HINGE_P2 = 2 };
00099 enum { ROT_DIR_CLOCKWISE = 1 };
00100 enum { ROT_DIR_COUNTERCLOCKWISE = 2 };
00101 enum { LOCKED = 1 };
00102 enum { LATCHED = 2 };
00103 enum { UNLATCHED = 3 };
00104
00105 private:
00106 static const char* __s_getDataType_() { return "door_msgs/Door"; }
00107 public:
00108 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00109
00110 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00111
00112 private:
00113 static const char* __s_getMD5Sum_() { return "19464ad3b8e608fe8e2ff8a6ec098603"; }
00114 public:
00115 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00116
00117 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00118
00119 private:
00120 static const char* __s_getMessageDefinition_() { return "Header header\n\
00121 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00122 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00123 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00124 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00125 geometry_msgs/Point32 handle ## Position of the door handle\n\
00126 float32 height ## Height of the door\n\
00127 \n\
00128 int32 UNKNOWN=0\n\
00129 \n\
00130 int32 HINGE_P1=1\n\
00131 int32 HINGE_P2=2\n\
00132 int32 hinge \n\
00133 \n\
00134 int32 ROT_DIR_CLOCKWISE=1\n\
00135 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00136 int32 rot_dir \n\
00137 \n\
00138 int32 LOCKED=1\n\
00139 int32 LATCHED=2\n\
00140 int32 UNLATCHED=3\n\
00141 int32 latch_state \n\
00142 \n\
00143 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00144 float32 weight ## @Sachin: what do we use this for?\n\
00145 \n\
00146 \n\
00147 \n\
00148 ================================================================================\n\
00149 MSG: std_msgs/Header\n\
00150 # Standard metadata for higher-level stamped data types.\n\
00151 # This is generally used to communicate timestamped data \n\
00152 # in a particular coordinate frame.\n\
00153 # \n\
00154 # sequence ID: consecutively increasing ID \n\
00155 uint32 seq\n\
00156 #Two-integer timestamp that is expressed as:\n\
00157 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00158 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00159 # time-handling sugar is provided by the client library\n\
00160 time stamp\n\
00161 #Frame this data is associated with\n\
00162 # 0: no frame\n\
00163 # 1: global frame\n\
00164 string frame_id\n\
00165 \n\
00166 ================================================================================\n\
00167 MSG: geometry_msgs/Point32\n\
00168 # This contains the position of a point in free space(with 32 bits of precision).\n\
00169 # It is recommeded to use Point wherever possible instead of Point32. \n\
00170 # \n\
00171 # This recommendation is to promote interoperability. \n\
00172 #\n\
00173 # This message is designed to take up less space when sending\n\
00174 # lots of points at once, as in the case of a PointCloud. \n\
00175 \n\
00176 float32 x\n\
00177 float32 y\n\
00178 float32 z\n\
00179 ================================================================================\n\
00180 MSG: geometry_msgs/Vector3\n\
00181 # This represents a vector in free space. \n\
00182 \n\
00183 float64 x\n\
00184 float64 y\n\
00185 float64 z\n\
00186 "; }
00187 public:
00188 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00189
00190 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00191
00192 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00193 {
00194 ros::serialization::OStream stream(write_ptr, 1000000000);
00195 ros::serialization::serialize(stream, header);
00196 ros::serialization::serialize(stream, frame_p1);
00197 ros::serialization::serialize(stream, frame_p2);
00198 ros::serialization::serialize(stream, door_p1);
00199 ros::serialization::serialize(stream, door_p2);
00200 ros::serialization::serialize(stream, handle);
00201 ros::serialization::serialize(stream, height);
00202 ros::serialization::serialize(stream, hinge);
00203 ros::serialization::serialize(stream, rot_dir);
00204 ros::serialization::serialize(stream, latch_state);
00205 ros::serialization::serialize(stream, travel_dir);
00206 ros::serialization::serialize(stream, weight);
00207 return stream.getData();
00208 }
00209
00210 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00211 {
00212 ros::serialization::IStream stream(read_ptr, 1000000000);
00213 ros::serialization::deserialize(stream, header);
00214 ros::serialization::deserialize(stream, frame_p1);
00215 ros::serialization::deserialize(stream, frame_p2);
00216 ros::serialization::deserialize(stream, door_p1);
00217 ros::serialization::deserialize(stream, door_p2);
00218 ros::serialization::deserialize(stream, handle);
00219 ros::serialization::deserialize(stream, height);
00220 ros::serialization::deserialize(stream, hinge);
00221 ros::serialization::deserialize(stream, rot_dir);
00222 ros::serialization::deserialize(stream, latch_state);
00223 ros::serialization::deserialize(stream, travel_dir);
00224 ros::serialization::deserialize(stream, weight);
00225 return stream.getData();
00226 }
00227
00228 ROS_DEPRECATED virtual uint32_t serializationLength() const
00229 {
00230 uint32_t size = 0;
00231 size += ros::serialization::serializationLength(header);
00232 size += ros::serialization::serializationLength(frame_p1);
00233 size += ros::serialization::serializationLength(frame_p2);
00234 size += ros::serialization::serializationLength(door_p1);
00235 size += ros::serialization::serializationLength(door_p2);
00236 size += ros::serialization::serializationLength(handle);
00237 size += ros::serialization::serializationLength(height);
00238 size += ros::serialization::serializationLength(hinge);
00239 size += ros::serialization::serializationLength(rot_dir);
00240 size += ros::serialization::serializationLength(latch_state);
00241 size += ros::serialization::serializationLength(travel_dir);
00242 size += ros::serialization::serializationLength(weight);
00243 return size;
00244 }
00245
00246 typedef boost::shared_ptr< ::door_msgs::Door_<ContainerAllocator> > Ptr;
00247 typedef boost::shared_ptr< ::door_msgs::Door_<ContainerAllocator> const> ConstPtr;
00248 };
00249 typedef ::door_msgs::Door_<std::allocator<void> > Door;
00250
00251 typedef boost::shared_ptr< ::door_msgs::Door> DoorPtr;
00252 typedef boost::shared_ptr< ::door_msgs::Door const> DoorConstPtr;
00253
00254
00255 template<typename ContainerAllocator>
00256 std::ostream& operator<<(std::ostream& s, const ::door_msgs::Door_<ContainerAllocator> & v)
00257 {
00258 ros::message_operations::Printer< ::door_msgs::Door_<ContainerAllocator> >::stream(s, "", v);
00259 return s;}
00260
00261 }
00262
00263 namespace ros
00264 {
00265 namespace message_traits
00266 {
00267 template<class ContainerAllocator>
00268 struct MD5Sum< ::door_msgs::Door_<ContainerAllocator> > {
00269 static const char* value()
00270 {
00271 return "19464ad3b8e608fe8e2ff8a6ec098603";
00272 }
00273
00274 static const char* value(const ::door_msgs::Door_<ContainerAllocator> &) { return value(); }
00275 static const uint64_t static_value1 = 0x19464ad3b8e608feULL;
00276 static const uint64_t static_value2 = 0x8e2ff8a6ec098603ULL;
00277 };
00278
00279 template<class ContainerAllocator>
00280 struct DataType< ::door_msgs::Door_<ContainerAllocator> > {
00281 static const char* value()
00282 {
00283 return "door_msgs/Door";
00284 }
00285
00286 static const char* value(const ::door_msgs::Door_<ContainerAllocator> &) { return value(); }
00287 };
00288
00289 template<class ContainerAllocator>
00290 struct Definition< ::door_msgs::Door_<ContainerAllocator> > {
00291 static const char* value()
00292 {
00293 return "Header header\n\
00294 geometry_msgs/Point32 frame_p1 ## position of the door frame\n\
00295 geometry_msgs/Point32 frame_p2 ## position of the door frame\n\
00296 geometry_msgs/Point32 door_p1 ## Ground plane projection of a point on the plane of the door \n\
00297 geometry_msgs/Point32 door_p2 ## Ground plane projection of a point on the plane of the door\n\
00298 geometry_msgs/Point32 handle ## Position of the door handle\n\
00299 float32 height ## Height of the door\n\
00300 \n\
00301 int32 UNKNOWN=0\n\
00302 \n\
00303 int32 HINGE_P1=1\n\
00304 int32 HINGE_P2=2\n\
00305 int32 hinge \n\
00306 \n\
00307 int32 ROT_DIR_CLOCKWISE=1\n\
00308 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00309 int32 rot_dir \n\
00310 \n\
00311 int32 LOCKED=1\n\
00312 int32 LATCHED=2\n\
00313 int32 UNLATCHED=3\n\
00314 int32 latch_state \n\
00315 \n\
00316 geometry_msgs/Vector3 travel_dir ## vector pointing in the direction the robot is going to travel through the door\n\
00317 float32 weight ## @Sachin: what do we use this for?\n\
00318 \n\
00319 \n\
00320 \n\
00321 ================================================================================\n\
00322 MSG: std_msgs/Header\n\
00323 # Standard metadata for higher-level stamped data types.\n\
00324 # This is generally used to communicate timestamped data \n\
00325 # in a particular coordinate frame.\n\
00326 # \n\
00327 # sequence ID: consecutively increasing ID \n\
00328 uint32 seq\n\
00329 #Two-integer timestamp that is expressed as:\n\
00330 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00331 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00332 # time-handling sugar is provided by the client library\n\
00333 time stamp\n\
00334 #Frame this data is associated with\n\
00335 # 0: no frame\n\
00336 # 1: global frame\n\
00337 string frame_id\n\
00338 \n\
00339 ================================================================================\n\
00340 MSG: geometry_msgs/Point32\n\
00341 # This contains the position of a point in free space(with 32 bits of precision).\n\
00342 # It is recommeded to use Point wherever possible instead of Point32. \n\
00343 # \n\
00344 # This recommendation is to promote interoperability. \n\
00345 #\n\
00346 # This message is designed to take up less space when sending\n\
00347 # lots of points at once, as in the case of a PointCloud. \n\
00348 \n\
00349 float32 x\n\
00350 float32 y\n\
00351 float32 z\n\
00352 ================================================================================\n\
00353 MSG: geometry_msgs/Vector3\n\
00354 # This represents a vector in free space. \n\
00355 \n\
00356 float64 x\n\
00357 float64 y\n\
00358 float64 z\n\
00359 ";
00360 }
00361
00362 static const char* value(const ::door_msgs::Door_<ContainerAllocator> &) { return value(); }
00363 };
00364
00365 template<class ContainerAllocator> struct HasHeader< ::door_msgs::Door_<ContainerAllocator> > : public TrueType {};
00366 template<class ContainerAllocator> struct HasHeader< const ::door_msgs::Door_<ContainerAllocator> > : public TrueType {};
00367 }
00368 }
00369
00370 namespace ros
00371 {
00372 namespace serialization
00373 {
00374
00375 template<class ContainerAllocator> struct Serializer< ::door_msgs::Door_<ContainerAllocator> >
00376 {
00377 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00378 {
00379 stream.next(m.header);
00380 stream.next(m.frame_p1);
00381 stream.next(m.frame_p2);
00382 stream.next(m.door_p1);
00383 stream.next(m.door_p2);
00384 stream.next(m.handle);
00385 stream.next(m.height);
00386 stream.next(m.hinge);
00387 stream.next(m.rot_dir);
00388 stream.next(m.latch_state);
00389 stream.next(m.travel_dir);
00390 stream.next(m.weight);
00391 }
00392
00393 ROS_DECLARE_ALLINONE_SERIALIZER;
00394 };
00395 }
00396 }
00397
00398 namespace ros
00399 {
00400 namespace message_operations
00401 {
00402
00403 template<class ContainerAllocator>
00404 struct Printer< ::door_msgs::Door_<ContainerAllocator> >
00405 {
00406 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::door_msgs::Door_<ContainerAllocator> & v)
00407 {
00408 s << indent << "header: ";
00409 s << std::endl;
00410 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00411 s << indent << "frame_p1: ";
00412 s << std::endl;
00413 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.frame_p1);
00414 s << indent << "frame_p2: ";
00415 s << std::endl;
00416 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.frame_p2);
00417 s << indent << "door_p1: ";
00418 s << std::endl;
00419 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.door_p1);
00420 s << indent << "door_p2: ";
00421 s << std::endl;
00422 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.door_p2);
00423 s << indent << "handle: ";
00424 s << std::endl;
00425 Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + " ", v.handle);
00426 s << indent << "height: ";
00427 Printer<float>::stream(s, indent + " ", v.height);
00428 s << indent << "hinge: ";
00429 Printer<int32_t>::stream(s, indent + " ", v.hinge);
00430 s << indent << "rot_dir: ";
00431 Printer<int32_t>::stream(s, indent + " ", v.rot_dir);
00432 s << indent << "latch_state: ";
00433 Printer<int32_t>::stream(s, indent + " ", v.latch_state);
00434 s << indent << "travel_dir: ";
00435 s << std::endl;
00436 Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + " ", v.travel_dir);
00437 s << indent << "weight: ";
00438 Printer<float>::stream(s, indent + " ", v.weight);
00439 }
00440 };
00441
00442
00443 }
00444 }
00445
00446 #endif // DOOR_MSGS_MESSAGE_DOOR_H
00447