Go to the documentation of this file.
6 #ifndef NAV_MSGS_MESSAGE_ODOMETRY_H
7 #define NAV_MSGS_MESSAGE_ODOMETRY_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
25 template <
class ContainerAllocator>
49 typedef std::basic_string<char, std::char_traits<char>,
typename ContainerAllocator::template rebind<char>::other >
_child_frame_id_type;
52 typedef ::geometry_msgs::PoseWithCovariance_<ContainerAllocator>
_pose_type;
55 typedef ::geometry_msgs::TwistWithCovariance_<ContainerAllocator>
_twist_type;
62 typedef std::shared_ptr< ::nav_msgs::Odometry_<ContainerAllocator> >
Ptr;
63 typedef std::shared_ptr< ::nav_msgs::Odometry_<ContainerAllocator>
const>
ConstPtr;
67 typedef ::nav_msgs::Odometry_<std::allocator<void> >
Odometry;
76 template<
typename ContainerAllocator>
77 std::ostream&
operator<<(std::ostream& s, const ::nav_msgs::Odometry_<ContainerAllocator> & v)
84 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
85 bool operator==(const ::nav_msgs::Odometry_<ContainerAllocator1> & lhs, const ::nav_msgs::Odometry_<ContainerAllocator2> & rhs)
87 return lhs.header == rhs.header &&
88 lhs.child_frame_id == rhs.child_frame_id &&
89 lhs.pose == rhs.pose &&
90 lhs.twist == rhs.twist;
93 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
94 bool operator!=(const ::nav_msgs::Odometry_<ContainerAllocator1> & lhs, const ::nav_msgs::Odometry_<ContainerAllocator2> & rhs)
104 namespace message_traits
111 template <
class ContainerAllocator>
116 template <
class ContainerAllocator>
121 template <
class ContainerAllocator>
126 template <
class ContainerAllocator>
131 template <
class ContainerAllocator>
136 template <
class ContainerAllocator>
142 template<
class ContainerAllocator>
147 return "cd5e73d190d741a2f92e81eda573aca7";
150 static const char*
value(const ::nav_msgs::Odometry_<ContainerAllocator>&) {
return value(); }
151 static const uint64_t static_value1 = 0xcd5e73d190d741a2ULL;
152 static const uint64_t static_value2 = 0xf92e81eda573aca7ULL;
155 template<
class ContainerAllocator>
160 return "nav_msgs/Odometry";
163 static const char*
value(const ::nav_msgs::Odometry_<ContainerAllocator>&) {
return value(); }
166 template<
class ContainerAllocator>
171 return "# This represents an estimate of a position and velocity in free space. \n"
172 "# The pose in this message should be specified in the coordinate frame given by header.frame_id.\n"
173 "# The twist in this message should be specified in the coordinate frame given by the child_frame_id\n"
175 "string child_frame_id\n"
176 "geometry_msgs/PoseWithCovariance pose\n"
177 "geometry_msgs/TwistWithCovariance twist\n"
179 "================================================================================\n"
180 "MSG: std_msgs/Header\n"
181 "# Standard metadata for higher-level stamped data types.\n"
182 "# This is generally used to communicate timestamped data \n"
183 "# in a particular coordinate frame.\n"
185 "# sequence ID: consecutively increasing ID \n"
187 "#Two-integer timestamp that is expressed as:\n"
188 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
189 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
190 "# time-handling sugar is provided by the client library\n"
192 "#Frame this data is associated with\n"
195 "================================================================================\n"
196 "MSG: geometry_msgs/PoseWithCovariance\n"
197 "# This represents a pose in free space with uncertainty.\n"
201 "# Row-major representation of the 6x6 covariance matrix\n"
202 "# The orientation parameters use a fixed-axis representation.\n"
203 "# In order, the parameters are:\n"
204 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
205 "float64[36] covariance\n"
207 "================================================================================\n"
208 "MSG: geometry_msgs/Pose\n"
209 "# A representation of pose in free space, composed of position and orientation. \n"
211 "Quaternion orientation\n"
213 "================================================================================\n"
214 "MSG: geometry_msgs/Point\n"
215 "# This contains the position of a point in free space\n"
220 "================================================================================\n"
221 "MSG: geometry_msgs/Quaternion\n"
222 "# This represents an orientation in free space in quaternion form.\n"
229 "================================================================================\n"
230 "MSG: geometry_msgs/TwistWithCovariance\n"
231 "# This expresses velocity in free space with uncertainty.\n"
235 "# Row-major representation of the 6x6 covariance matrix\n"
236 "# The orientation parameters use a fixed-axis representation.\n"
237 "# In order, the parameters are:\n"
238 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
239 "float64[36] covariance\n"
241 "================================================================================\n"
242 "MSG: geometry_msgs/Twist\n"
243 "# This expresses velocity in free space broken into its linear and angular parts.\n"
247 "================================================================================\n"
248 "MSG: geometry_msgs/Vector3\n"
249 "# This represents a vector in free space. \n"
250 "# It is only meant to represent a direction. Therefore, it does not\n"
251 "# make sense to apply a translation to it (e.g., when applying a \n"
252 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
253 "# rotation). If you want your data to be translatable too, use the\n"
254 "# geometry_msgs/Point message instead.\n"
262 static const char*
value(const ::nav_msgs::Odometry_<ContainerAllocator>&) {
return value(); }
270 namespace serialization
275 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
277 stream.next(m.header);
278 stream.next(m.child_frame_id);
280 stream.next(m.twist);
291 namespace message_operations
294 template<
class ContainerAllocator>
297 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::nav_msgs::Odometry_<ContainerAllocator>& v)
302 s <<
indent <<
"child_frame_id: ";
316 #endif // NAV_MSGS_MESSAGE_ODOMETRY_H
static const char * value(const ::nav_msgs::Odometry_< ContainerAllocator > &)
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
::std_msgs::Header_< ContainerAllocator > _header_type
static void stream(Stream &s, const std::string &indent, const ::nav_msgs::Odometry_< ContainerAllocator > &v)
Templated serialization class. Default implementation provides backwards compatibility with old messa...
std::shared_ptr< ::nav_msgs::Odometry_< ContainerAllocator > > Ptr
std::shared_ptr< ::nav_msgs::Odometry_< ContainerAllocator > const > ConstPtr
::geometry_msgs::TwistWithCovariance_< ContainerAllocator > _twist_type
static void stream(Stream &s, const std::string &indent, const M &value)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
std::shared_ptr< ::nav_msgs::Odometry const > OdometryConstPtr
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > _child_frame_id_type
std::ostream & operator<<(std::ostream &s, const ::nav_msgs::GetMapAction_< ContainerAllocator > &v)
Specialize to provide the datatype for a message.
::nav_msgs::Odometry_< std::allocator< void > > Odometry
Specialize to provide the definition for a message.
static const char * value()
_child_frame_id_type child_frame_id
static void allInOne(Stream &stream, T m)
Odometry_< ContainerAllocator > Type
static const char * value(const ::nav_msgs::Odometry_< ContainerAllocator > &)
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
static const char * value()
bool operator==(const ::nav_msgs::GetMapAction_< ContainerAllocator1 > &lhs, const ::nav_msgs::GetMapAction_< ContainerAllocator2 > &rhs)
std::shared_ptr< ::nav_msgs::Odometry > OdometryPtr
Stream base-class, provides common functionality for IStream and OStream.
static const char * value(const ::nav_msgs::Odometry_< ContainerAllocator > &)
::geometry_msgs::PoseWithCovariance_< ContainerAllocator > _pose_type
bool operator!=(const ::nav_msgs::GetMapAction_< ContainerAllocator1 > &lhs, const ::nav_msgs::GetMapAction_< ContainerAllocator2 > &rhs)
static const char * value()
Odometry_(const ContainerAllocator &_alloc)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09