30#include <fastcdr/Cdr.h>
32#include <fastcdr/exceptions/BadParamException.h>
33using namespace eprosima::fastcdr::exception;
37#define geometry_msgs_msg_TwistWithCovariance_max_cdr_typesize 336ULL;
38#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL;
39#define geometry_msgs_msg_Pose_max_cdr_typesize 56ULL;
40#define std_msgs_msg_Time_max_cdr_typesize 8ULL;
41#define nav_msgs_msg_Odometry_max_cdr_typesize 1208ULL;
42#define geometry_msgs_msg_Twist_max_cdr_typesize 48ULL;
43#define geometry_msgs_msg_Point_max_cdr_typesize 24ULL;
44#define geometry_msgs_msg_PoseWithCovariance_max_cdr_typesize 344ULL;
45#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL;
46#define std_msgs_msg_Header_max_cdr_typesize 268ULL;
47#define geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize 0ULL;
48#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL;
49#define geometry_msgs_msg_Pose_max_key_cdr_typesize 0ULL;
50#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL;
51#define nav_msgs_msg_Odometry_max_key_cdr_typesize 0ULL;
52#define geometry_msgs_msg_Twist_max_key_cdr_typesize 0ULL;
53#define geometry_msgs_msg_Point_max_key_cdr_typesize 0ULL;
54#define geometry_msgs_msg_PoseWithCovariance_max_key_cdr_typesize 0ULL;
55#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL;
56#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL;
85 m_header = std::move(x.m_header);
86 m_child_frame_id = std::move(x.m_child_frame_id);
87 m_pose = std::move(x.m_pose);
88 m_twist = std::move(x.m_twist);
116 m_header = std::move(x.m_header);
118 m_child_frame_id = std::move(x.m_child_frame_id);
120 m_pose = std::move(x.m_pose);
122 m_twist = std::move(x.m_twist);
140 return !(*
this == x);
176 eprosima::fastcdr::Cdr& scdr)
const
181 scdr << m_child_frame_id.c_str();
190 eprosima::fastcdr::Cdr& dcdr)
195 dcdr >> m_child_frame_id;
207 const std_msgs::msg::Header& _header)
217 std_msgs::msg::Header&& _header)
219 m_header = std::move(_header);
244 const std::string& _child_frame_id)
246 m_child_frame_id = _child_frame_id;
254 std::string&& _child_frame_id)
256 m_child_frame_id = std::move(_child_frame_id);
265 return m_child_frame_id;
274 return m_child_frame_id;
294 m_pose = std::move(_pose);
332 m_twist = std::move(_twist);
373 eprosima::fastcdr::Cdr& scdr)
const
#define nav_msgs_msg_Odometry_max_cdr_typesize
#define nav_msgs_msg_Odometry_max_key_cdr_typesize
return current_alignment initial_alignment
This class represents the structure PoseWithCovariance defined by the user in the IDL file.
static eProsima_user_DllExport size_t getCdrSerializedSize(const geometry_msgs::msg::PoseWithCovariance &data, size_t current_alignment=0)
This function returns the serialized size of a data depending on the buffer alignment.
此类表示用户在 IDL 文件中定义的 TwistWithCovariance 结构。 <>
static eProsima_user_DllExport size_t getCdrSerializedSize(const geometry_msgs::msg::TwistWithCovariance &data, size_t current_alignment=0)
返回数据的序列化大小(取决于缓冲区对齐)。
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 pose(const geometry_msgs::msg::PoseWithCovariance &_pose)
This function copies the value in member pose
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...
eProsima_user_DllExport void twist(const geometry_msgs::msg::TwistWithCovariance &_twist)
This function copies the value in member twist
static eProsima_user_DllExport bool isKeyDefined()
This function tells you if the Key has been defined for this type
eProsima_user_DllExport void header(const std_msgs::msg::Header &_header)
This function copies the value in member header
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.
eProsima_user_DllExport void child_frame_id(const std::string &_child_frame_id)
This function copies the value in member child_frame_id
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.