Ros2DynamicMessage#

Fully qualified name: isaacsim::ros2::bridge::Ros2DynamicMessage

class Ros2DynamicMessage : public isaacsim::ros2::bridge::Ros2Message#

Class implementing dynamic ROS 2 messages.

This class allows to define and use ROS 2 message types at runtime, rather than at compile time.

Warning

Processing the message as JSON has a significative computation overhead compared to processing it as a vector.

Public Functions

virtual std::string generateSummary(bool print) = 0#

Generate a human-readable summary of the dynamic message structure and print it (configurable)

Message: sensor_msgs/msg/PointCloud2 (topic | message)
Idx Array ROS type                  OGN type                  Name
=== ===== ========================= ========================= ====
0   no    INT32 (int32_t)           eInt (int32_t)            header:stamp:sec
1   no    UINT32 (uint32_t)         eUInt (uint32_t)          header:stamp:nanosec
2   no    STRING (std::string)      eToken (std::string)      header:frame_id
3   no    UINT32 (uint32_t)         eUInt (uint32_t)          height
4   no    UINT32 (uint32_t)         eUInt (uint32_t)          width
5   yes   MESSAGE (nlohmann::json)  eUnknown (nlohmann::json) fields
6   no    BOOLEAN (bool)            eBool (bool)              is_bigendian
7   no    UINT32 (uint32_t)         eUInt (uint32_t)          point_step
8   no    UINT32 (uint32_t)         eUInt (uint32_t)          row_step
9   yes   UINT8 (uint8_t)           eUInt (uint32_t)          data
10  no    BOOLEAN (bool)            eBool (bool)              is_dense
Parameters:

print – Whether to print the human-readable structure of the dynamic message to the console.

Returns:

A human-readable tabular structure of the dynamic message.

virtual const nlohmann::json &readData() = 0#

Read the message fields value and return them contained in a JSON object.

Returns:

Message data as JSON.

virtual const std::vector<std::shared_ptr<void>> &readData(
bool asOgnType,
) = 0#

Read the message fields value and return them contained in a vector of shared pointers object.

Parameters:

asOgnType – Whether the pointers point to OmniGraph or ROS 2 specific data types.

Returns:

Message data as vector of shared pointers.

virtual void writeData(const nlohmann::json &data) = 0#

Write the message fields value from a JSON object.

Parameters:

data – Message data as JSON.

virtual void writeData(
const std::vector<std::shared_ptr<void>> &data,
bool fromOgnType,
) = 0#

Write the message fields value from a vector of shared pointers object.

Parameters:
  • data – Message data as vector of shared pointers object.

  • fromOgnType – Whether the pointers point to OmniGraph or ROS 2 specific data types.

inline const std::vector<DynamicMessageField> &getMessageFields()#

Get the dynamic message fields description (DynamicMessageField).

Returns:

Message fields description.

inline const std::vector<std::shared_ptr<void>> &getVectorContainer(
bool asOgnType,
)#

Get the dynamic message container as vector of shared pointers.

The vector container is a constant vector of non-constant shared pointers. This means that the elements of the vector (the message fields) cannot be modified but their content (the message fields’ value) can. This is particularly useful when writing the message data using a vector as a container since it is not necessary to create pointers to the required data types. See Ros2DynamicMessage::writeData for use example.

Parameters:

asOgnType – Whether the pointers point to OmniGraph or ROS 2 specific data types.

Returns:

Message container as vector of shared pointers.

inline bool isValid()#

Check whether the ROS 2 message has been created and initialized properly.

Returns:

Whether the ROS 2 message has been created and initialized properly.

inline void *getPtr()#

Get the message pointer.

Returns:

The pointer to the message if it has been created and initialized properly, otherwise nullptr.

virtual const void *getTypeSupportHandle() = 0#

Get the pointer to the struct that contains the ROS IDL message type support data.

The pointer points to a ROS IDL struct if the message if founded.

Message type

ROS IDL struct

Topic (Message)

rosidl_message_type_support_t

Service

rosidl_service_type_support_t

Action

rosidl_action_type_support_t

Returns:

The pointer to the struct, otherwise nullptr.

Protected Attributes

std::vector<DynamicMessageField> m_messagesFields#

Message fields description.

nlohmann::json m_messageJsonContainer#

Message container as JSON.

std::vector<std::shared_ptr<void>> m_messageVectorRosContainer#

Message container as ROS 2-specific data types vector.

std::vector<std::shared_ptr<void>> m_messageVectorOgnContainer#

Message container as OmniGraph-specific data types vector.

void *m_msg = nullptr#

Message pointer.