30 #include <fastcdr/Cdr.h> 32 #include <fastcdr/exceptions/BadParamException.h> 37 #define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; 38 #define geometry_msgs_msg_Twist_max_cdr_typesize 48ULL; 39 #define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; 40 #define geometry_msgs_msg_Twist_max_key_cdr_typesize 0ULL; 60 m_linear = std::move(x.m_linear);
61 m_angular = std::move(x.m_angular);
76 m_linear = std::move(x.m_linear);
77 m_angular = std::move(x.m_angular);
95 size_t current_alignment)
97 static_cast<void>(current_alignment);
103 size_t current_alignment)
105 size_t initial_alignment = current_alignment;
109 return current_alignment - initial_alignment;
113 eprosima::fastcdr::Cdr& scdr)
const 120 eprosima::fastcdr::Cdr& dcdr)
143 m_linear = std::move(_linear);
171 m_angular = _angular;
181 m_angular = std::move(_angular);
204 size_t current_alignment)
206 static_cast<void>(current_alignment);
216 eprosima::fastcdr::Cdr& scdr)
const geometry_msgs::msg::Vector3 m_angular
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 void deserialize(eprosima::fastcdr::Cdr &cdr)
This function deserializes an object using CDR serialization.
#define geometry_msgs_msg_Twist_max_cdr_typesize
eProsima_user_DllExport ~Twist()
Default destructor.
eProsima_user_DllExport bool operator!=(const Twist &x) const
Comparison operator.
This class represents the structure Twist defined by the user in the IDL file.
eProsima_user_DllExport const geometry_msgs::msg::Vector3 & linear() const
This function returns a constant reference to member linear.
eProsima_user_DllExport Twist & operator=(const Twist &x)
Copy assignment.
#define geometry_msgs_msg_Twist_max_key_cdr_typesize
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...
This class represents the structure Vector3 defined by the user in the IDL file.
eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr &cdr) const
This function serializes an object using CDR serialization.
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 const geometry_msgs::msg::Vector3 & angular() const
This function returns a constant reference to member angular.
static eProsima_user_DllExport size_t getCdrSerializedSize(const geometry_msgs::msg::Twist &data, size_t current_alignment=0)
This function returns the serialized size of a data depending on the buffer alignment.
eProsima_user_DllExport bool operator==(const Twist &x) const
Comparison operator.
static eProsima_user_DllExport size_t getCdrSerializedSize(const geometry_msgs::msg::Vector3 &data, size_t current_alignment=0)
This function returns the serialized size of a data depending on the buffer alignment.
static eProsima_user_DllExport bool isKeyDefined()
This function tells you if the Key has been defined for this type.
eProsima_user_DllExport void linear(const geometry_msgs::msg::Vector3 &_linear)
This function copies the value in member linear.
eProsima_user_DllExport Twist()
Default constructor.
eProsima_user_DllExport void angular(const geometry_msgs::msg::Vector3 &_angular)
This function copies the value in member angular.
geometry_msgs::msg::Vector3 m_linear