Door.h
Go to the documentation of this file.
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-fuerte-pr2_doors/doc_stacks/2013-12-11_14-13-17.791847/pr2_doors/door_msgs/msg/Door.msg */
00002 #ifndef DOOR_MSGS_MESSAGE_DOOR_H
00003 #define DOOR_MSGS_MESSAGE_DOOR_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/Point32.h"
00019 #include "geometry_msgs/Point32.h"
00020 #include "geometry_msgs/Point32.h"
00021 #include "geometry_msgs/Point32.h"
00022 #include "geometry_msgs/Point32.h"
00023 #include "geometry_msgs/Vector3.h"
00024 
00025 namespace door_msgs
00026 {
00027 template <class ContainerAllocator>
00028 struct Door_ {
00029   typedef Door_<ContainerAllocator> Type;
00030 
00031   Door_()
00032   : header()
00033   , frame_p1()
00034   , frame_p2()
00035   , door_p1()
00036   , door_p2()
00037   , handle()
00038   , height(0.0)
00039   , hinge(0)
00040   , rot_dir(0)
00041   , latch_state(0)
00042   , travel_dir()
00043   , weight(0.0)
00044   {
00045   }
00046 
00047   Door_(const ContainerAllocator& _alloc)
00048   : header(_alloc)
00049   , frame_p1(_alloc)
00050   , frame_p2(_alloc)
00051   , door_p1(_alloc)
00052   , door_p2(_alloc)
00053   , handle(_alloc)
00054   , height(0.0)
00055   , hinge(0)
00056   , rot_dir(0)
00057   , latch_state(0)
00058   , travel_dir(_alloc)
00059   , weight(0.0)
00060   {
00061   }
00062 
00063   typedef  ::std_msgs::Header_<ContainerAllocator>  _header_type;
00064    ::std_msgs::Header_<ContainerAllocator>  header;
00065 
00066   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _frame_p1_type;
00067    ::geometry_msgs::Point32_<ContainerAllocator>  frame_p1;
00068 
00069   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _frame_p2_type;
00070    ::geometry_msgs::Point32_<ContainerAllocator>  frame_p2;
00071 
00072   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _door_p1_type;
00073    ::geometry_msgs::Point32_<ContainerAllocator>  door_p1;
00074 
00075   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _door_p2_type;
00076    ::geometry_msgs::Point32_<ContainerAllocator>  door_p2;
00077 
00078   typedef  ::geometry_msgs::Point32_<ContainerAllocator>  _handle_type;
00079    ::geometry_msgs::Point32_<ContainerAllocator>  handle;
00080 
00081   typedef float _height_type;
00082   float height;
00083 
00084   typedef int32_t _hinge_type;
00085   int32_t hinge;
00086 
00087   typedef int32_t _rot_dir_type;
00088   int32_t rot_dir;
00089 
00090   typedef int32_t _latch_state_type;
00091   int32_t latch_state;
00092 
00093   typedef  ::geometry_msgs::Vector3_<ContainerAllocator>  _travel_dir_type;
00094    ::geometry_msgs::Vector3_<ContainerAllocator>  travel_dir;
00095 
00096   typedef float _weight_type;
00097   float weight;
00098 
00099   enum { UNKNOWN = 0 };
00100   enum { HINGE_P1 = 1 };
00101   enum { HINGE_P2 = 2 };
00102   enum { ROT_DIR_CLOCKWISE = 1 };
00103   enum { ROT_DIR_COUNTERCLOCKWISE = 2 };
00104   enum { LOCKED = 1 };
00105   enum { LATCHED = 2 };
00106   enum { UNLATCHED = 3 };
00107 
00108   typedef boost::shared_ptr< ::door_msgs::Door_<ContainerAllocator> > Ptr;
00109   typedef boost::shared_ptr< ::door_msgs::Door_<ContainerAllocator>  const> ConstPtr;
00110   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00111 }; // struct Door
00112 typedef  ::door_msgs::Door_<std::allocator<void> > Door;
00113 
00114 typedef boost::shared_ptr< ::door_msgs::Door> DoorPtr;
00115 typedef boost::shared_ptr< ::door_msgs::Door const> DoorConstPtr;
00116 
00117 
00118 template<typename ContainerAllocator>
00119 std::ostream& operator<<(std::ostream& s, const  ::door_msgs::Door_<ContainerAllocator> & v)
00120 {
00121   ros::message_operations::Printer< ::door_msgs::Door_<ContainerAllocator> >::stream(s, "", v);
00122   return s;}
00123 
00124 } // namespace door_msgs
00125 
00126 namespace ros
00127 {
00128 namespace message_traits
00129 {
00130 template<class ContainerAllocator> struct IsMessage< ::door_msgs::Door_<ContainerAllocator> > : public TrueType {};
00131 template<class ContainerAllocator> struct IsMessage< ::door_msgs::Door_<ContainerAllocator>  const> : public TrueType {};
00132 template<class ContainerAllocator>
00133 struct MD5Sum< ::door_msgs::Door_<ContainerAllocator> > {
00134   static const char* value() 
00135   {
00136     return "19464ad3b8e608fe8e2ff8a6ec098603";
00137   }
00138 
00139   static const char* value(const  ::door_msgs::Door_<ContainerAllocator> &) { return value(); } 
00140   static const uint64_t static_value1 = 0x19464ad3b8e608feULL;
00141   static const uint64_t static_value2 = 0x8e2ff8a6ec098603ULL;
00142 };
00143 
00144 template<class ContainerAllocator>
00145 struct DataType< ::door_msgs::Door_<ContainerAllocator> > {
00146   static const char* value() 
00147   {
00148     return "door_msgs/Door";
00149   }
00150 
00151   static const char* value(const  ::door_msgs::Door_<ContainerAllocator> &) { return value(); } 
00152 };
00153 
00154 template<class ContainerAllocator>
00155 struct Definition< ::door_msgs::Door_<ContainerAllocator> > {
00156   static const char* value() 
00157   {
00158     return "Header header\n\
00159 geometry_msgs/Point32 frame_p1  ## position of the door frame\n\
00160 geometry_msgs/Point32 frame_p2  ## position of the door frame\n\
00161 geometry_msgs/Point32 door_p1   ## Ground plane projection of a point on the plane of the door \n\
00162 geometry_msgs/Point32 door_p2   ## Ground plane projection of a point on the plane of the door\n\
00163 geometry_msgs/Point32 handle    ## Position of the door handle\n\
00164 float32 height               ## Height of the door\n\
00165 \n\
00166 int32 UNKNOWN=0\n\
00167 \n\
00168 int32 HINGE_P1=1\n\
00169 int32 HINGE_P2=2\n\
00170 int32 hinge                  \n\
00171 \n\
00172 int32 ROT_DIR_CLOCKWISE=1\n\
00173 int32 ROT_DIR_COUNTERCLOCKWISE=2\n\
00174 int32 rot_dir                \n\
00175 \n\
00176 int32 LOCKED=1\n\
00177 int32 LATCHED=2\n\
00178 int32 UNLATCHED=3\n\
00179 int32 latch_state            \n\
00180 \n\
00181 geometry_msgs/Vector3 travel_dir           ## vector pointing in the direction the robot is going to travel through the door\n\
00182 float32 weight               ## @Sachin: what do we use this for?\n\
00183 \n\
00184 \n\
00185 \n\
00186 ================================================================================\n\
00187 MSG: std_msgs/Header\n\
00188 # Standard metadata for higher-level stamped data types.\n\
00189 # This is generally used to communicate timestamped data \n\
00190 # in a particular coordinate frame.\n\
00191 # \n\
00192 # sequence ID: consecutively increasing ID \n\
00193 uint32 seq\n\
00194 #Two-integer timestamp that is expressed as:\n\
00195 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00196 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00197 # time-handling sugar is provided by the client library\n\
00198 time stamp\n\
00199 #Frame this data is associated with\n\
00200 # 0: no frame\n\
00201 # 1: global frame\n\
00202 string frame_id\n\
00203 \n\
00204 ================================================================================\n\
00205 MSG: geometry_msgs/Point32\n\
00206 # This contains the position of a point in free space(with 32 bits of precision).\n\
00207 # It is recommeded to use Point wherever possible instead of Point32.  \n\
00208 # \n\
00209 # This recommendation is to promote interoperability.  \n\
00210 #\n\
00211 # This message is designed to take up less space when sending\n\
00212 # lots of points at once, as in the case of a PointCloud.  \n\
00213 \n\
00214 float32 x\n\
00215 float32 y\n\
00216 float32 z\n\
00217 ================================================================================\n\
00218 MSG: geometry_msgs/Vector3\n\
00219 # This represents a vector in free space. \n\
00220 \n\
00221 float64 x\n\
00222 float64 y\n\
00223 float64 z\n\
00224 ";
00225   }
00226 
00227   static const char* value(const  ::door_msgs::Door_<ContainerAllocator> &) { return value(); } 
00228 };
00229 
00230 template<class ContainerAllocator> struct HasHeader< ::door_msgs::Door_<ContainerAllocator> > : public TrueType {};
00231 template<class ContainerAllocator> struct HasHeader< const ::door_msgs::Door_<ContainerAllocator> > : public TrueType {};
00232 } // namespace message_traits
00233 } // namespace ros
00234 
00235 namespace ros
00236 {
00237 namespace serialization
00238 {
00239 
00240 template<class ContainerAllocator> struct Serializer< ::door_msgs::Door_<ContainerAllocator> >
00241 {
00242   template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00243   {
00244     stream.next(m.header);
00245     stream.next(m.frame_p1);
00246     stream.next(m.frame_p2);
00247     stream.next(m.door_p1);
00248     stream.next(m.door_p2);
00249     stream.next(m.handle);
00250     stream.next(m.height);
00251     stream.next(m.hinge);
00252     stream.next(m.rot_dir);
00253     stream.next(m.latch_state);
00254     stream.next(m.travel_dir);
00255     stream.next(m.weight);
00256   }
00257 
00258   ROS_DECLARE_ALLINONE_SERIALIZER;
00259 }; // struct Door_
00260 } // namespace serialization
00261 } // namespace ros
00262 
00263 namespace ros
00264 {
00265 namespace message_operations
00266 {
00267 
00268 template<class ContainerAllocator>
00269 struct Printer< ::door_msgs::Door_<ContainerAllocator> >
00270 {
00271   template<typename Stream> static void stream(Stream& s, const std::string& indent, const  ::door_msgs::Door_<ContainerAllocator> & v) 
00272   {
00273     s << indent << "header: ";
00274 s << std::endl;
00275     Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + "  ", v.header);
00276     s << indent << "frame_p1: ";
00277 s << std::endl;
00278     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.frame_p1);
00279     s << indent << "frame_p2: ";
00280 s << std::endl;
00281     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.frame_p2);
00282     s << indent << "door_p1: ";
00283 s << std::endl;
00284     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.door_p1);
00285     s << indent << "door_p2: ";
00286 s << std::endl;
00287     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.door_p2);
00288     s << indent << "handle: ";
00289 s << std::endl;
00290     Printer< ::geometry_msgs::Point32_<ContainerAllocator> >::stream(s, indent + "  ", v.handle);
00291     s << indent << "height: ";
00292     Printer<float>::stream(s, indent + "  ", v.height);
00293     s << indent << "hinge: ";
00294     Printer<int32_t>::stream(s, indent + "  ", v.hinge);
00295     s << indent << "rot_dir: ";
00296     Printer<int32_t>::stream(s, indent + "  ", v.rot_dir);
00297     s << indent << "latch_state: ";
00298     Printer<int32_t>::stream(s, indent + "  ", v.latch_state);
00299     s << indent << "travel_dir: ";
00300 s << std::endl;
00301     Printer< ::geometry_msgs::Vector3_<ContainerAllocator> >::stream(s, indent + "  ", v.travel_dir);
00302     s << indent << "weight: ";
00303     Printer<float>::stream(s, indent + "  ", v.weight);
00304   }
00305 };
00306 
00307 
00308 } // namespace message_operations
00309 } // namespace ros
00310 
00311 #endif // DOOR_MSGS_MESSAGE_DOOR_H
00312 


door_msgs
Author(s): Wim Meeussen
autogenerated on Wed Dec 11 2013 14:16:35