22#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_
23#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_
29#include <fastrtps/utils/fixed_size_string.hpp>
39#if defined(EPROSIMA_USER_DLL_EXPORT)
40#define eProsima_user_DllExport __declspec( dllexport )
42#define eProsima_user_DllExport
45#define eProsima_user_DllExport
49#if defined(EPROSIMA_USER_DLL_EXPORT)
50#if defined(Odometry_SOURCE)
51#define Odometry_DllAPI __declspec( dllexport )
53#define Odometry_DllAPI __declspec( dllimport )
56#define Odometry_DllAPI
59#define Odometry_DllAPI
135 const std_msgs::msg::Header& _header);
142 std_msgs::msg::Header&& _header);
160 const std::string& _child_frame_id);
167 std::string&& _child_frame_id);
255 eprosima::fastcdr::Cdr& cdr)
const;
262 eprosima::fastcdr::Cdr& cdr);
283 eprosima::fastcdr::Cdr& cdr)
const;
#define eProsima_user_DllExport
This class represents the structure PoseWithCovariance defined by the user in the IDL file.
此类表示用户在 IDL 文件中定义的 TwistWithCovariance 结构。 <>
This class represents the structure Odometry defined by the user in the IDL file.
eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr &cdr) const
This function serializes the key members of an object using CDR serialization.
eProsima_user_DllExport const std::string & child_frame_id() const
This function returns a constant reference to member child_frame_id
std_msgs::msg::Header m_header
std::string m_child_frame_id
eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr &cdr)
This function deserializes an object using CDR serialization.
geometry_msgs::msg::PoseWithCovariance m_pose
eProsima_user_DllExport const geometry_msgs::msg::PoseWithCovariance & pose() const
This function returns a constant reference to member pose
eProsima_user_DllExport bool operator==(const Odometry &x) const
Comparison operator.
eProsima_user_DllExport ~Odometry()
Default destructor.
eProsima_user_DllExport bool operator!=(const Odometry &x) const
Comparison operator.
static eProsima_user_DllExport size_t getKeyMaxCdrSerializedSize(size_t current_alignment=0)
This function returns the maximum serialized size of the Key of an object depending on the buffer ali...
static eProsima_user_DllExport bool isKeyDefined()
This function tells you if the Key has been defined for this type
eProsima_user_DllExport const std_msgs::msg::Header & header() const
This function returns a constant reference to member header
eProsima_user_DllExport Odometry()
Default constructor.
static eProsima_user_DllExport size_t getCdrSerializedSize(const nav_msgs::msg::Odometry &data, size_t current_alignment=0)
This function returns the serialized size of a data depending on the buffer alignment.
geometry_msgs::msg::TwistWithCovariance m_twist
eProsima_user_DllExport Odometry & operator=(const Odometry &x)
Copy assignment.
eProsima_user_DllExport const geometry_msgs::msg::TwistWithCovariance & twist() const
This function returns a constant reference to member twist
static eProsima_user_DllExport size_t getMaxCdrSerializedSize(size_t current_alignment=0)
This function returns the maximum serialized size of an object depending on the buffer alignment.
eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr &cdr) const
This function serializes an object using CDR serialization.