#include <Odometry.h>
Public Types | |
| typedef std::basic_string< char, std::char_traits< char >, typename ContainerAllocator::template rebind< char >::other > | _child_frame_id_type |
| typedef ::std_msgs::Header_< ContainerAllocator > | _header_type |
| typedef ::geometry_msgs::PoseWithCovariance_< ContainerAllocator > | _pose_type |
| typedef ::geometry_msgs::TwistWithCovariance_< ContainerAllocator > | _twist_type |
| typedef std::shared_ptr< ::nav_msgs::Odometry_< ContainerAllocator > const > | ConstPtr |
| typedef std::shared_ptr< ::nav_msgs::Odometry_< ContainerAllocator > > | Ptr |
| typedef Odometry_< ContainerAllocator > | Type |
Public Member Functions | |
| Odometry_ () | |
| Odometry_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
| _child_frame_id_type | child_frame_id |
| _header_type | header |
| _pose_type | pose |
| _twist_type | twist |
Definition at line 26 of file Odometry.h.
| typedef std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > nav_msgs::Odometry_< ContainerAllocator >::_child_frame_id_type |
Definition at line 49 of file Odometry.h.
| typedef ::std_msgs::Header_<ContainerAllocator> nav_msgs::Odometry_< ContainerAllocator >::_header_type |
Definition at line 46 of file Odometry.h.
| typedef ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> nav_msgs::Odometry_< ContainerAllocator >::_pose_type |
Definition at line 52 of file Odometry.h.
| typedef ::geometry_msgs::TwistWithCovariance_<ContainerAllocator> nav_msgs::Odometry_< ContainerAllocator >::_twist_type |
Definition at line 55 of file Odometry.h.
| typedef std::shared_ptr< ::nav_msgs::Odometry_<ContainerAllocator> const> nav_msgs::Odometry_< ContainerAllocator >::ConstPtr |
Definition at line 63 of file Odometry.h.
| typedef std::shared_ptr< ::nav_msgs::Odometry_<ContainerAllocator> > nav_msgs::Odometry_< ContainerAllocator >::Ptr |
Definition at line 62 of file Odometry.h.
| typedef Odometry_<ContainerAllocator> nav_msgs::Odometry_< ContainerAllocator >::Type |
Definition at line 28 of file Odometry.h.
|
inline |
Definition at line 30 of file Odometry.h.
|
inline |
Definition at line 36 of file Odometry.h.
| _child_frame_id_type nav_msgs::Odometry_< ContainerAllocator >::child_frame_id |
Definition at line 50 of file Odometry.h.
| _header_type nav_msgs::Odometry_< ContainerAllocator >::header |
Definition at line 47 of file Odometry.h.
| _pose_type nav_msgs::Odometry_< ContainerAllocator >::pose |
Definition at line 53 of file Odometry.h.
| _twist_type nav_msgs::Odometry_< ContainerAllocator >::twist |
Definition at line 56 of file Odometry.h.