This class represents the structure Header defined by the user in the IDL file. More...
#include <Header.h>
Public Member Functions | |
eProsima_user_DllExport void | deserialize (eprosima::fastcdr::Cdr &cdr) |
This function deserializes an object using CDR serialization. More... | |
eProsima_user_DllExport void | frame_id (const std::string &_frame_id) |
This function copies the value in member frame_id. More... | |
eProsima_user_DllExport void | frame_id (std::string &&_frame_id) |
This function moves the value in member frame_id. More... | |
eProsima_user_DllExport const std::string & | frame_id () const |
This function returns a constant reference to member frame_id. More... | |
eProsima_user_DllExport std::string & | frame_id () |
This function returns a reference to member frame_id. More... | |
eProsima_user_DllExport | Header () |
Default constructor. More... | |
eProsima_user_DllExport | Header (const Header &x) |
Copy constructor. More... | |
eProsima_user_DllExport | Header (Header &&x) noexcept |
Move constructor. More... | |
eProsima_user_DllExport bool | operator!= (const Header &x) const |
Comparison operator. More... | |
eProsima_user_DllExport Header & | operator= (const Header &x) |
Copy assignment. More... | |
eProsima_user_DllExport Header & | operator= (Header &&x) noexcept |
Move assignment. More... | |
eProsima_user_DllExport bool | operator== (const Header &x) const |
Comparison operator. More... | |
eProsima_user_DllExport void | serialize (eprosima::fastcdr::Cdr &cdr) const |
This function serializes an object using CDR serialization. More... | |
eProsima_user_DllExport void | serializeKey (eprosima::fastcdr::Cdr &cdr) const |
This function serializes the key members of an object using CDR serialization. More... | |
eProsima_user_DllExport void | stamp (const builtin_interfaces::msg::Time &_stamp) |
This function copies the value in member stamp. More... | |
eProsima_user_DllExport void | stamp (builtin_interfaces::msg::Time &&_stamp) |
This function moves the value in member stamp. More... | |
eProsima_user_DllExport const builtin_interfaces::msg::Time & | stamp () const |
This function returns a constant reference to member stamp. More... | |
eProsima_user_DllExport builtin_interfaces::msg::Time & | stamp () |
This function returns a reference to member stamp. More... | |
eProsima_user_DllExport | ~Header () |
Default destructor. More... | |
Static Public Member Functions | |
static eProsima_user_DllExport size_t | getCdrSerializedSize (const std_msgs::msg::Header &data, size_t current_alignment=0) |
This function returns the serialized size of a data depending on the buffer alignment. More... | |
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 alignment. More... | |
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. More... | |
static eProsima_user_DllExport bool | isKeyDefined () |
This function tells you if the Key has been defined for this type. More... | |
Private Attributes | |
std::string | m_frame_id |
builtin_interfaces::msg::Time | m_stamp |
This class represents the structure Header defined by the user in the IDL file.
std_msgs::msg::Header::Header | ( | ) |
Default constructor.
Definition at line 42 of file Header.cpp.
std_msgs::msg::Header::~Header | ( | ) |
Default destructor.
Definition at line 47 of file Header.cpp.
std_msgs::msg::Header::Header | ( | const Header & | x | ) |
Copy constructor.
x | Reference to the object std_msgs::msg::Header that will be copied. |
Definition at line 51 of file Header.cpp.
References m_frame_id, and m_stamp.
|
noexcept |
Move constructor.
x | Reference to the object std_msgs::msg::Header that will be copied. |
Definition at line 58 of file Header.cpp.
void std_msgs::msg::Header::deserialize | ( | eprosima::fastcdr::Cdr & | cdr | ) |
This function deserializes an object using CDR serialization.
cdr | CDR serialization object. |
Definition at line 120 of file Header.cpp.
Referenced by std_msgs::msg::HeaderPubSubType::deserialize().
void std_msgs::msg::Header::frame_id | ( | const std::string & | _frame_id | ) |
This function copies the value in member frame_id.
_frame_id | New value to be copied in member frame_id |
Definition at line 168 of file Header.cpp.
Referenced by getCdrSerializedSize(), carla::ros2::CarlaDepthCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaRGBCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaISCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaSSCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaNormalsCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaOpticalFlowCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaDVSCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaLineInvasionPublisher::SetData(), carla::ros2::CarlaGNSSPublisher::SetData(), carla::ros2::CarlaIMUPublisher::SetData(), carla::ros2::CarlaTransformPublisher::SetData(), carla::ros2::CarlaRadarPublisher::SetData(), carla::ros2::CarlaSemanticLidarPublisher::SetData(), carla::ros2::CarlaLidarPublisher::SetData(), carla::ros2::CarlaCollisionPublisher::SetData(), carla::ros2::CarlaISCameraPublisher::SetData(), carla::ros2::CarlaSSCameraPublisher::SetData(), carla::ros2::CarlaDepthCameraPublisher::SetData(), carla::ros2::CarlaOpticalFlowCameraPublisher::SetData(), carla::ros2::CarlaNormalsCameraPublisher::SetData(), carla::ros2::CarlaDVSCameraPublisher::SetData(), and carla::ros2::CarlaRGBCameraPublisher::SetImageData().
void std_msgs::msg::Header::frame_id | ( | std::string && | _frame_id | ) |
This function moves the value in member frame_id.
_frame_id | New value to be moved in member frame_id |
Definition at line 178 of file Header.cpp.
const std::string & std_msgs::msg::Header::frame_id | ( | ) | const |
This function returns a constant reference to member frame_id.
Definition at line 188 of file Header.cpp.
std::string & std_msgs::msg::Header::frame_id | ( | ) |
This function returns a reference to member frame_id.
Definition at line 197 of file Header.cpp.
|
static |
This function returns the serialized size of a data depending on the buffer alignment.
data | Data which is calculated its serialized size. |
current_alignment | Buffer alignment. |
Definition at line 102 of file Header.cpp.
References frame_id(), builtin_interfaces::msg::Time::getCdrSerializedSize(), and stamp().
Referenced by carla_msgs::msg::LaneInvasionEvent::getCdrSerializedSize(), carla_msgs::msg::CarlaCollisionEvent::getCdrSerializedSize(), geometry_msgs::msg::TransformStamped::getCdrSerializedSize(), nav_msgs::msg::Odometry::getCdrSerializedSize(), sensor_msgs::msg::Image::getCdrSerializedSize(), sensor_msgs::msg::NavSatFix::getCdrSerializedSize(), carla_msgs::msg::CarlaEgoVehicleControl::getCdrSerializedSize(), sensor_msgs::msg::Imu::getCdrSerializedSize(), sensor_msgs::msg::PointCloud2::getCdrSerializedSize(), sensor_msgs::msg::CameraInfo::getCdrSerializedSize(), and std_msgs::msg::HeaderPubSubType::getSerializedSizeProvider().
|
static |
This function returns the maximum serialized size of the Key of an object depending on the buffer alignment.
current_alignment | Buffer alignment. |
Definition at line 203 of file Header.cpp.
References std_msgs_msg_Header_max_key_cdr_typesize.
Referenced by std_msgs::msg::HeaderPubSubType::getKey(), and std_msgs::msg::HeaderPubSubType::HeaderPubSubType().
|
static |
This function returns the maximum serialized size of an object depending on the buffer alignment.
current_alignment | Buffer alignment. |
Definition at line 95 of file Header.cpp.
References std_msgs_msg_Header_max_cdr_typesize.
Referenced by std_msgs::msg::HeaderPubSubType::HeaderPubSubType().
|
static |
This function tells you if the Key has been defined for this type.
Definition at line 210 of file Header.cpp.
Referenced by std_msgs::msg::HeaderPubSubType::HeaderPubSubType().
bool std_msgs::msg::Header::operator!= | ( | const Header & | x | ) | const |
Comparison operator.
x | std_msgs::msg::Header object to compare. |
Definition at line 89 of file Header.cpp.
std_msgs::msg::Header & std_msgs::msg::Header::operator= | ( | const Header & | x | ) |
Copy assignment.
x | Reference to the object std_msgs::msg::Header that will be copied. |
Definition at line 65 of file Header.cpp.
References m_frame_id, and m_stamp.
|
noexcept |
Move assignment.
x | Reference to the object std_msgs::msg::Header that will be copied. |
Definition at line 74 of file Header.cpp.
bool std_msgs::msg::Header::operator== | ( | const Header & | x | ) | const |
Comparison operator.
x | std_msgs::msg::Header object to compare. |
Definition at line 83 of file Header.cpp.
References m_frame_id, and m_stamp.
void std_msgs::msg::Header::serialize | ( | eprosima::fastcdr::Cdr & | cdr | ) | const |
This function serializes an object using CDR serialization.
cdr | CDR serialization object. |
Definition at line 113 of file Header.cpp.
Referenced by std_msgs::msg::HeaderPubSubType::serialize().
void std_msgs::msg::Header::serializeKey | ( | eprosima::fastcdr::Cdr & | cdr | ) | const |
This function serializes the key members of an object using CDR serialization.
cdr | CDR serialization object. |
Definition at line 215 of file Header.cpp.
Referenced by std_msgs::msg::HeaderPubSubType::getKey().
void std_msgs::msg::Header::stamp | ( | const builtin_interfaces::msg::Time & | _stamp | ) |
This function copies the value in member stamp.
_stamp | New value to be copied in member stamp |
Definition at line 131 of file Header.cpp.
Referenced by getCdrSerializedSize(), carla::ros2::CarlaDepthCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaRGBCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaISCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaSSCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaNormalsCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaOpticalFlowCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaDVSCameraPublisher::SetCameraInfoData(), carla::ros2::CarlaLineInvasionPublisher::SetData(), carla::ros2::CarlaGNSSPublisher::SetData(), carla::ros2::CarlaIMUPublisher::SetData(), carla::ros2::CarlaTransformPublisher::SetData(), carla::ros2::CarlaRadarPublisher::SetData(), carla::ros2::CarlaSemanticLidarPublisher::SetData(), carla::ros2::CarlaLidarPublisher::SetData(), carla::ros2::CarlaCollisionPublisher::SetData(), carla::ros2::CarlaISCameraPublisher::SetData(), carla::ros2::CarlaSSCameraPublisher::SetData(), carla::ros2::CarlaDepthCameraPublisher::SetData(), carla::ros2::CarlaOpticalFlowCameraPublisher::SetData(), carla::ros2::CarlaNormalsCameraPublisher::SetData(), carla::ros2::CarlaDVSCameraPublisher::SetData(), and carla::ros2::CarlaRGBCameraPublisher::SetImageData().
void std_msgs::msg::Header::stamp | ( | builtin_interfaces::msg::Time && | _stamp | ) |
This function moves the value in member stamp.
_stamp | New value to be moved in member stamp |
Definition at line 141 of file Header.cpp.
const builtin_interfaces::msg::Time & std_msgs::msg::Header::stamp | ( | ) | const |
This function returns a constant reference to member stamp.
Definition at line 151 of file Header.cpp.
builtin_interfaces::msg::Time & std_msgs::msg::Header::stamp | ( | ) |
This function returns a reference to member stamp.
Definition at line 160 of file Header.cpp.
|
private |
Definition at line 235 of file Header.h.
Referenced by Header(), operator=(), and operator==().
|
private |
Definition at line 234 of file Header.h.
Referenced by Header(), operator=(), and operator==().