$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-humanoid_walk/doc_stacks/2013-03-01_15-40-38.607083/humanoid_walk/walk_msgs/msg/WalkPath.msg */ 00002 #ifndef WALK_MSGS_MESSAGE_WALKPATH_H 00003 #define WALK_MSGS_MESSAGE_WALKPATH_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 "nav_msgs/Path.h" 00018 #include "nav_msgs/Path.h" 00019 #include "walk_msgs/PathPoint3d.h" 00020 #include "walk_msgs/PathPoint2d.h" 00021 00022 namespace walk_msgs 00023 { 00024 template <class ContainerAllocator> 00025 struct WalkPath_ { 00026 typedef WalkPath_<ContainerAllocator> Type; 00027 00028 WalkPath_() 00029 : left_foot() 00030 , right_foot() 00031 , center_of_mass() 00032 , zmp() 00033 { 00034 } 00035 00036 WalkPath_(const ContainerAllocator& _alloc) 00037 : left_foot(_alloc) 00038 , right_foot(_alloc) 00039 , center_of_mass(_alloc) 00040 , zmp(_alloc) 00041 { 00042 } 00043 00044 typedef ::nav_msgs::Path_<ContainerAllocator> _left_foot_type; 00045 ::nav_msgs::Path_<ContainerAllocator> left_foot; 00046 00047 typedef ::nav_msgs::Path_<ContainerAllocator> _right_foot_type; 00048 ::nav_msgs::Path_<ContainerAllocator> right_foot; 00049 00050 typedef ::walk_msgs::PathPoint3d_<ContainerAllocator> _center_of_mass_type; 00051 ::walk_msgs::PathPoint3d_<ContainerAllocator> center_of_mass; 00052 00053 typedef ::walk_msgs::PathPoint2d_<ContainerAllocator> _zmp_type; 00054 ::walk_msgs::PathPoint2d_<ContainerAllocator> zmp; 00055 00056 00057 private: 00058 static const char* __s_getDataType_() { return "walk_msgs/WalkPath"; } 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 "d0a0a99ccf67829c6bd2a9f0499ae76e"; } 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 "nav_msgs/Path left_foot\n\ 00073 nav_msgs/Path right_foot\n\ 00074 walk_msgs/PathPoint3d center_of_mass\n\ 00075 walk_msgs/PathPoint2d zmp\n\ 00076 \n\ 00077 ================================================================================\n\ 00078 MSG: nav_msgs/Path\n\ 00079 #An array of poses that represents a Path for a robot to follow\n\ 00080 Header header\n\ 00081 geometry_msgs/PoseStamped[] poses\n\ 00082 \n\ 00083 ================================================================================\n\ 00084 MSG: std_msgs/Header\n\ 00085 # Standard metadata for higher-level stamped data types.\n\ 00086 # This is generally used to communicate timestamped data \n\ 00087 # in a particular coordinate frame.\n\ 00088 # \n\ 00089 # sequence ID: consecutively increasing ID \n\ 00090 uint32 seq\n\ 00091 #Two-integer timestamp that is expressed as:\n\ 00092 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00093 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00094 # time-handling sugar is provided by the client library\n\ 00095 time stamp\n\ 00096 #Frame this data is associated with\n\ 00097 # 0: no frame\n\ 00098 # 1: global frame\n\ 00099 string frame_id\n\ 00100 \n\ 00101 ================================================================================\n\ 00102 MSG: geometry_msgs/PoseStamped\n\ 00103 # A Pose with reference coordinate frame and timestamp\n\ 00104 Header header\n\ 00105 Pose pose\n\ 00106 \n\ 00107 ================================================================================\n\ 00108 MSG: geometry_msgs/Pose\n\ 00109 # A representation of pose in free space, composed of postion and orientation. \n\ 00110 Point position\n\ 00111 Quaternion orientation\n\ 00112 \n\ 00113 ================================================================================\n\ 00114 MSG: geometry_msgs/Point\n\ 00115 # This contains the position of a point in free space\n\ 00116 float64 x\n\ 00117 float64 y\n\ 00118 float64 z\n\ 00119 \n\ 00120 ================================================================================\n\ 00121 MSG: geometry_msgs/Quaternion\n\ 00122 # This represents an orientation in free space in quaternion form.\n\ 00123 \n\ 00124 float64 x\n\ 00125 float64 y\n\ 00126 float64 z\n\ 00127 float64 w\n\ 00128 \n\ 00129 ================================================================================\n\ 00130 MSG: walk_msgs/PathPoint3d\n\ 00131 Header header\n\ 00132 geometry_msgs/PointStamped[] points\n\ 00133 \n\ 00134 ================================================================================\n\ 00135 MSG: geometry_msgs/PointStamped\n\ 00136 # This represents a Point with reference coordinate frame and timestamp\n\ 00137 Header header\n\ 00138 Point point\n\ 00139 \n\ 00140 ================================================================================\n\ 00141 MSG: walk_msgs/PathPoint2d\n\ 00142 Header header\n\ 00143 walk_msgs/Point2dStamped[] points\n\ 00144 \n\ 00145 ================================================================================\n\ 00146 MSG: walk_msgs/Point2dStamped\n\ 00147 Header header\n\ 00148 Point2d point\n\ 00149 \n\ 00150 ================================================================================\n\ 00151 MSG: walk_msgs/Point2d\n\ 00152 float64 x\n\ 00153 float64 y\n\ 00154 \n\ 00155 "; } 00156 public: 00157 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00158 00159 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00160 00161 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00162 { 00163 ros::serialization::OStream stream(write_ptr, 1000000000); 00164 ros::serialization::serialize(stream, left_foot); 00165 ros::serialization::serialize(stream, right_foot); 00166 ros::serialization::serialize(stream, center_of_mass); 00167 ros::serialization::serialize(stream, zmp); 00168 return stream.getData(); 00169 } 00170 00171 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00172 { 00173 ros::serialization::IStream stream(read_ptr, 1000000000); 00174 ros::serialization::deserialize(stream, left_foot); 00175 ros::serialization::deserialize(stream, right_foot); 00176 ros::serialization::deserialize(stream, center_of_mass); 00177 ros::serialization::deserialize(stream, zmp); 00178 return stream.getData(); 00179 } 00180 00181 ROS_DEPRECATED virtual uint32_t serializationLength() const 00182 { 00183 uint32_t size = 0; 00184 size += ros::serialization::serializationLength(left_foot); 00185 size += ros::serialization::serializationLength(right_foot); 00186 size += ros::serialization::serializationLength(center_of_mass); 00187 size += ros::serialization::serializationLength(zmp); 00188 return size; 00189 } 00190 00191 typedef boost::shared_ptr< ::walk_msgs::WalkPath_<ContainerAllocator> > Ptr; 00192 typedef boost::shared_ptr< ::walk_msgs::WalkPath_<ContainerAllocator> const> ConstPtr; 00193 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00194 }; // struct WalkPath 00195 typedef ::walk_msgs::WalkPath_<std::allocator<void> > WalkPath; 00196 00197 typedef boost::shared_ptr< ::walk_msgs::WalkPath> WalkPathPtr; 00198 typedef boost::shared_ptr< ::walk_msgs::WalkPath const> WalkPathConstPtr; 00199 00200 00201 template<typename ContainerAllocator> 00202 std::ostream& operator<<(std::ostream& s, const ::walk_msgs::WalkPath_<ContainerAllocator> & v) 00203 { 00204 ros::message_operations::Printer< ::walk_msgs::WalkPath_<ContainerAllocator> >::stream(s, "", v); 00205 return s;} 00206 00207 } // namespace walk_msgs 00208 00209 namespace ros 00210 { 00211 namespace message_traits 00212 { 00213 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::WalkPath_<ContainerAllocator> > : public TrueType {}; 00214 template<class ContainerAllocator> struct IsMessage< ::walk_msgs::WalkPath_<ContainerAllocator> const> : public TrueType {}; 00215 template<class ContainerAllocator> 00216 struct MD5Sum< ::walk_msgs::WalkPath_<ContainerAllocator> > { 00217 static const char* value() 00218 { 00219 return "d0a0a99ccf67829c6bd2a9f0499ae76e"; 00220 } 00221 00222 static const char* value(const ::walk_msgs::WalkPath_<ContainerAllocator> &) { return value(); } 00223 static const uint64_t static_value1 = 0xd0a0a99ccf67829cULL; 00224 static const uint64_t static_value2 = 0x6bd2a9f0499ae76eULL; 00225 }; 00226 00227 template<class ContainerAllocator> 00228 struct DataType< ::walk_msgs::WalkPath_<ContainerAllocator> > { 00229 static const char* value() 00230 { 00231 return "walk_msgs/WalkPath"; 00232 } 00233 00234 static const char* value(const ::walk_msgs::WalkPath_<ContainerAllocator> &) { return value(); } 00235 }; 00236 00237 template<class ContainerAllocator> 00238 struct Definition< ::walk_msgs::WalkPath_<ContainerAllocator> > { 00239 static const char* value() 00240 { 00241 return "nav_msgs/Path left_foot\n\ 00242 nav_msgs/Path right_foot\n\ 00243 walk_msgs/PathPoint3d center_of_mass\n\ 00244 walk_msgs/PathPoint2d zmp\n\ 00245 \n\ 00246 ================================================================================\n\ 00247 MSG: nav_msgs/Path\n\ 00248 #An array of poses that represents a Path for a robot to follow\n\ 00249 Header header\n\ 00250 geometry_msgs/PoseStamped[] poses\n\ 00251 \n\ 00252 ================================================================================\n\ 00253 MSG: std_msgs/Header\n\ 00254 # Standard metadata for higher-level stamped data types.\n\ 00255 # This is generally used to communicate timestamped data \n\ 00256 # in a particular coordinate frame.\n\ 00257 # \n\ 00258 # sequence ID: consecutively increasing ID \n\ 00259 uint32 seq\n\ 00260 #Two-integer timestamp that is expressed as:\n\ 00261 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00262 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00263 # time-handling sugar is provided by the client library\n\ 00264 time stamp\n\ 00265 #Frame this data is associated with\n\ 00266 # 0: no frame\n\ 00267 # 1: global frame\n\ 00268 string frame_id\n\ 00269 \n\ 00270 ================================================================================\n\ 00271 MSG: geometry_msgs/PoseStamped\n\ 00272 # A Pose with reference coordinate frame and timestamp\n\ 00273 Header header\n\ 00274 Pose pose\n\ 00275 \n\ 00276 ================================================================================\n\ 00277 MSG: geometry_msgs/Pose\n\ 00278 # A representation of pose in free space, composed of postion and orientation. \n\ 00279 Point position\n\ 00280 Quaternion orientation\n\ 00281 \n\ 00282 ================================================================================\n\ 00283 MSG: geometry_msgs/Point\n\ 00284 # This contains the position of a point in free space\n\ 00285 float64 x\n\ 00286 float64 y\n\ 00287 float64 z\n\ 00288 \n\ 00289 ================================================================================\n\ 00290 MSG: geometry_msgs/Quaternion\n\ 00291 # This represents an orientation in free space in quaternion form.\n\ 00292 \n\ 00293 float64 x\n\ 00294 float64 y\n\ 00295 float64 z\n\ 00296 float64 w\n\ 00297 \n\ 00298 ================================================================================\n\ 00299 MSG: walk_msgs/PathPoint3d\n\ 00300 Header header\n\ 00301 geometry_msgs/PointStamped[] points\n\ 00302 \n\ 00303 ================================================================================\n\ 00304 MSG: geometry_msgs/PointStamped\n\ 00305 # This represents a Point with reference coordinate frame and timestamp\n\ 00306 Header header\n\ 00307 Point point\n\ 00308 \n\ 00309 ================================================================================\n\ 00310 MSG: walk_msgs/PathPoint2d\n\ 00311 Header header\n\ 00312 walk_msgs/Point2dStamped[] points\n\ 00313 \n\ 00314 ================================================================================\n\ 00315 MSG: walk_msgs/Point2dStamped\n\ 00316 Header header\n\ 00317 Point2d point\n\ 00318 \n\ 00319 ================================================================================\n\ 00320 MSG: walk_msgs/Point2d\n\ 00321 float64 x\n\ 00322 float64 y\n\ 00323 \n\ 00324 "; 00325 } 00326 00327 static const char* value(const ::walk_msgs::WalkPath_<ContainerAllocator> &) { return value(); } 00328 }; 00329 00330 } // namespace message_traits 00331 } // namespace ros 00332 00333 namespace ros 00334 { 00335 namespace serialization 00336 { 00337 00338 template<class ContainerAllocator> struct Serializer< ::walk_msgs::WalkPath_<ContainerAllocator> > 00339 { 00340 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00341 { 00342 stream.next(m.left_foot); 00343 stream.next(m.right_foot); 00344 stream.next(m.center_of_mass); 00345 stream.next(m.zmp); 00346 } 00347 00348 ROS_DECLARE_ALLINONE_SERIALIZER; 00349 }; // struct WalkPath_ 00350 } // namespace serialization 00351 } // namespace ros 00352 00353 namespace ros 00354 { 00355 namespace message_operations 00356 { 00357 00358 template<class ContainerAllocator> 00359 struct Printer< ::walk_msgs::WalkPath_<ContainerAllocator> > 00360 { 00361 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::walk_msgs::WalkPath_<ContainerAllocator> & v) 00362 { 00363 s << indent << "left_foot: "; 00364 s << std::endl; 00365 Printer< ::nav_msgs::Path_<ContainerAllocator> >::stream(s, indent + " ", v.left_foot); 00366 s << indent << "right_foot: "; 00367 s << std::endl; 00368 Printer< ::nav_msgs::Path_<ContainerAllocator> >::stream(s, indent + " ", v.right_foot); 00369 s << indent << "center_of_mass: "; 00370 s << std::endl; 00371 Printer< ::walk_msgs::PathPoint3d_<ContainerAllocator> >::stream(s, indent + " ", v.center_of_mass); 00372 s << indent << "zmp: "; 00373 s << std::endl; 00374 Printer< ::walk_msgs::PathPoint2d_<ContainerAllocator> >::stream(s, indent + " ", v.zmp); 00375 } 00376 }; 00377 00378 00379 } // namespace message_operations 00380 } // namespace ros 00381 00382 #endif // WALK_MSGS_MESSAGE_WALKPATH_H 00383