00001
00002 #ifndef MOVE_BASE_MSGS_MESSAGE_MOVEBASEFEEDBACK_H
00003 #define MOVE_BASE_MSGS_MESSAGE_MOVEBASEFEEDBACK_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 "geometry_msgs/PoseStamped.h"
00014
00015 namespace move_base_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct MoveBaseFeedback_ : public ros::Message
00019 {
00020 typedef MoveBaseFeedback_<ContainerAllocator> Type;
00021
00022 MoveBaseFeedback_()
00023 : base_position()
00024 {
00025 }
00026
00027 MoveBaseFeedback_(const ContainerAllocator& _alloc)
00028 : base_position(_alloc)
00029 {
00030 }
00031
00032 typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> _base_position_type;
00033 ::geometry_msgs::PoseStamped_<ContainerAllocator> base_position;
00034
00035
00036 private:
00037 static const char* __s_getDataType_() { return "move_base_msgs/MoveBaseFeedback"; }
00038 public:
00039 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00040
00041 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00042
00043 private:
00044 static const char* __s_getMD5Sum_() { return "3fb824c456a757373a226f6d08071bf0"; }
00045 public:
00046 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00047
00048 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00049
00050 private:
00051 static const char* __s_getMessageDefinition_() { return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00052 geometry_msgs/PoseStamped base_position\n\
00053 \n\
00054 \n\
00055 ================================================================================\n\
00056 MSG: geometry_msgs/PoseStamped\n\
00057 # A Pose with reference coordinate frame and timestamp\n\
00058 Header header\n\
00059 Pose pose\n\
00060 \n\
00061 ================================================================================\n\
00062 MSG: std_msgs/Header\n\
00063 # Standard metadata for higher-level stamped data types.\n\
00064 # This is generally used to communicate timestamped data \n\
00065 # in a particular coordinate frame.\n\
00066 # \n\
00067 # sequence ID: consecutively increasing ID \n\
00068 uint32 seq\n\
00069 #Two-integer timestamp that is expressed as:\n\
00070 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00071 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00072 # time-handling sugar is provided by the client library\n\
00073 time stamp\n\
00074 #Frame this data is associated with\n\
00075 # 0: no frame\n\
00076 # 1: global frame\n\
00077 string frame_id\n\
00078 \n\
00079 ================================================================================\n\
00080 MSG: geometry_msgs/Pose\n\
00081 # A representation of pose in free space, composed of postion and orientation. \n\
00082 Point position\n\
00083 Quaternion orientation\n\
00084 \n\
00085 ================================================================================\n\
00086 MSG: geometry_msgs/Point\n\
00087 # This contains the position of a point in free space\n\
00088 float64 x\n\
00089 float64 y\n\
00090 float64 z\n\
00091 \n\
00092 ================================================================================\n\
00093 MSG: geometry_msgs/Quaternion\n\
00094 # This represents an orientation in free space in quaternion form.\n\
00095 \n\
00096 float64 x\n\
00097 float64 y\n\
00098 float64 z\n\
00099 float64 w\n\
00100 \n\
00101 "; }
00102 public:
00103 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00104
00105 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00106
00107 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00108 {
00109 ros::serialization::OStream stream(write_ptr, 1000000000);
00110 ros::serialization::serialize(stream, base_position);
00111 return stream.getData();
00112 }
00113
00114 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00115 {
00116 ros::serialization::IStream stream(read_ptr, 1000000000);
00117 ros::serialization::deserialize(stream, base_position);
00118 return stream.getData();
00119 }
00120
00121 ROS_DEPRECATED virtual uint32_t serializationLength() const
00122 {
00123 uint32_t size = 0;
00124 size += ros::serialization::serializationLength(base_position);
00125 return size;
00126 }
00127
00128 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> > Ptr;
00129 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> const> ConstPtr;
00130 };
00131 typedef ::move_base_msgs::MoveBaseFeedback_<std::allocator<void> > MoveBaseFeedback;
00132
00133 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseFeedback> MoveBaseFeedbackPtr;
00134 typedef boost::shared_ptr< ::move_base_msgs::MoveBaseFeedback const> MoveBaseFeedbackConstPtr;
00135
00136
00137 template<typename ContainerAllocator>
00138 std::ostream& operator<<(std::ostream& s, const ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> & v)
00139 {
00140 ros::message_operations::Printer< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> >::stream(s, "", v);
00141 return s;}
00142
00143 }
00144
00145 namespace ros
00146 {
00147 namespace message_traits
00148 {
00149 template<class ContainerAllocator>
00150 struct MD5Sum< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> > {
00151 static const char* value()
00152 {
00153 return "3fb824c456a757373a226f6d08071bf0";
00154 }
00155
00156 static const char* value(const ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> &) { return value(); }
00157 static const uint64_t static_value1 = 0x3fb824c456a75737ULL;
00158 static const uint64_t static_value2 = 0x3a226f6d08071bf0ULL;
00159 };
00160
00161 template<class ContainerAllocator>
00162 struct DataType< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> > {
00163 static const char* value()
00164 {
00165 return "move_base_msgs/MoveBaseFeedback";
00166 }
00167
00168 static const char* value(const ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> &) { return value(); }
00169 };
00170
00171 template<class ContainerAllocator>
00172 struct Definition< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> > {
00173 static const char* value()
00174 {
00175 return "# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n\
00176 geometry_msgs/PoseStamped base_position\n\
00177 \n\
00178 \n\
00179 ================================================================================\n\
00180 MSG: geometry_msgs/PoseStamped\n\
00181 # A Pose with reference coordinate frame and timestamp\n\
00182 Header header\n\
00183 Pose pose\n\
00184 \n\
00185 ================================================================================\n\
00186 MSG: std_msgs/Header\n\
00187 # Standard metadata for higher-level stamped data types.\n\
00188 # This is generally used to communicate timestamped data \n\
00189 # in a particular coordinate frame.\n\
00190 # \n\
00191 # sequence ID: consecutively increasing ID \n\
00192 uint32 seq\n\
00193 #Two-integer timestamp that is expressed as:\n\
00194 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00195 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00196 # time-handling sugar is provided by the client library\n\
00197 time stamp\n\
00198 #Frame this data is associated with\n\
00199 # 0: no frame\n\
00200 # 1: global frame\n\
00201 string frame_id\n\
00202 \n\
00203 ================================================================================\n\
00204 MSG: geometry_msgs/Pose\n\
00205 # A representation of pose in free space, composed of postion and orientation. \n\
00206 Point position\n\
00207 Quaternion orientation\n\
00208 \n\
00209 ================================================================================\n\
00210 MSG: geometry_msgs/Point\n\
00211 # This contains the position of a point in free space\n\
00212 float64 x\n\
00213 float64 y\n\
00214 float64 z\n\
00215 \n\
00216 ================================================================================\n\
00217 MSG: geometry_msgs/Quaternion\n\
00218 # This represents an orientation in free space in quaternion form.\n\
00219 \n\
00220 float64 x\n\
00221 float64 y\n\
00222 float64 z\n\
00223 float64 w\n\
00224 \n\
00225 ";
00226 }
00227
00228 static const char* value(const ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> &) { return value(); }
00229 };
00230
00231 }
00232 }
00233
00234 namespace ros
00235 {
00236 namespace serialization
00237 {
00238
00239 template<class ContainerAllocator> struct Serializer< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> >
00240 {
00241 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00242 {
00243 stream.next(m.base_position);
00244 }
00245
00246 ROS_DECLARE_ALLINONE_SERIALIZER;
00247 };
00248 }
00249 }
00250
00251 namespace ros
00252 {
00253 namespace message_operations
00254 {
00255
00256 template<class ContainerAllocator>
00257 struct Printer< ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> >
00258 {
00259 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::move_base_msgs::MoveBaseFeedback_<ContainerAllocator> & v)
00260 {
00261 s << indent << "base_position: ";
00262 s << std::endl;
00263 Printer< ::geometry_msgs::PoseStamped_<ContainerAllocator> >::stream(s, indent + " ", v.base_position);
00264 }
00265 };
00266
00267
00268 }
00269 }
00270
00271 #endif // MOVE_BASE_MSGS_MESSAGE_MOVEBASEFEEDBACK_H
00272