ROS2 Bridge [omni.isaac.ros2_bridge]

Omnigraph Nodes

OmniGraph Nodes

ROS2CameraInfoHelper

This node automates the CameraInfo message pipeline for monocular and stereo cameras.

Inputs
  • execIn (execution): Triggering this causes the sensor pipeline to be generated.

  • enabled (bool): True to enable the camera helper, False to disable. Default to True.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • frameId (string): FrameId for ROS2 message from the monocular or left stereo camera. Default to sim_camera.

  • topicName (string): Topic name for the monocular or left stereo camera data. Default to camera_info.

  • renderProductPath (token): Path of the render product used for capturing data from the monocular or left stereo camera.

  • frameIdRight (string, optional): FrameId for ROS2 message from the right stereo camera. Default to sim_camera_right.

  • topicNameRight (string, optional): Topic name for the right stereo camera data. Default to camera_info_right.

  • renderProductPathRight (token, optional): Path of the render product used for capturing data from the right stereo camera.

  • resetSimulationTimeOnStop (bool): If True the simulation time will reset when stop is pressed, False means time increases monotonically. This setting is ignored if useSystemTime is enabled. Default to False.

  • useSystemTime (bool): If True, system timestamp will be included in messages. If False, simulation timestamp will be included in messages. Default to False.

  • frameSkipCount (uint): Specifies the number of simulation frames to skip between each message publish. (e.g. Set to 0 to publish each frame. Set 1 to publish every other frame). Default to 0.

ROS2QoSProfile

This node generates a JSON config of a QoS Profile

Inputs
  • history (token): History policy. Default to keepLast.

  • depth (uint64): Depth (Queue size) policy. Only honored if the’history’ policy was set to ‘keepLast’. Default to 10.

  • reliability (token): Reliability policy. Default to reliable.

  • durability (token): Durability policy. Default to volatile.

  • deadline (double): Deadline policy. Defined in seconds. Default to 0.0.

  • lifespan (double): Lifespan policy. Defined in seconds. Default to 0.0.

  • liveliness (token): Liveliness policy. Default to systemDefault.

  • leaseDuration (double): Lease Duration policy. Defined in seconds. Default to 0.0.

  • createProfile (token): Preset profile configs. Choosing a QoS profile will update the policies accordingly. Default to defaultPubSub.

Outputs
  • qosProfile (string): QoS profile config.

ROS2RtxLidarHelper

Handles automation of Lidar Sensor pipeline

Inputs
  • execIn (execution): Triggering this causes the sensor pipeline to be generated.

  • enabled (bool): True to enable the lidar helper, False to disable. Default to True.

  • context (uint64): ROS2 context handle, default of zero will use the global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends and published/subscribed topic by the node namespace.

  • frameId (string): FrameID for the ROS2 message, the nodeNamespace will not be prefixed to the frame id. Default to sim_lidar.

  • topicName (string): Topic name for sensor data. Default to scan.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): Number of message to queue up before throwing away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • renderProductPath (token): Name of the render product path to publish lidar data.

  • type (token): Data to publish from node. Default to laser_scan.

  • resetSimulationTimeOnStop (bool): If True the simulation time will reset when stop is pressed, False means time increases monotonically. This setting is ignored if useSystemTime is enabled. Default to False.

  • fullScan (bool): If True publish a full scan when enough data has accumulated instead of partial scans each frame. Supports point cloud type only. Default to False.

  • showDebugView (bool): If True a debug view of the lidar particles will appear in the scene. Default to False.

  • useSystemTime (bool): If True, system timestamp will be included in messages. If False, simulation timestamp will be included in messages. Default to False.

  • frameSkipCount (uint): Specifies the number of simulation frames to skip between each message publish. (e.g. Set to 0 to publish each frame. Set 1 to publish every other frame). Default to 0.

ROS2CameraHelper

This node handles automation of the camera sensor pipeline

Inputs
  • execIn (execution): Triggering this causes the sensor pipeline to be generated.

  • enabled (bool): True to enable the camera helper, False to disable. Default to True.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message, the nodeNamespace will not be prefixed to the frame id. Default to sim_camera.

  • topicName (string): Topic name for sensor data. Default to rgb.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • viewport (token): DEPRECATED, use renderProductPath. Name of the desired viewport to publish.

  • renderProductPath (token): Path of the render product used for capturing data.

  • type (token): type. Default to rgb.

  • enableSemanticLabels (bool): Enable publishing of semantic labels, applies only to instance_segmentation, semantic_segmentation, bbox_2d_tight, bbox_2d_loose, bbox_3d.

  • semanticLabelsTopicName (string): Topic name used for publishing semantic labels, applies only to instance_segmentation, semantic_segmentation, bbox_2d_tight, bbox_2d_loose, bbox_3d. Default to semantic_labels.

  • stereoOffset (float[2]): Stereo offset is the baseline between cameras in x and y component of the image plane in meters. (Tx, Ty is calculated using x and y component of StereoOffset value. i.e., Tx=fx*stereoOffset.X, Ty=fy*stereoOffset.Y). Used when publishing to the camera info topic. Default to [0, 0].

  • resetSimulationTimeOnStop (bool): If True the simulation time will reset when stop is pressed, False means time increases monotonically. This setting is ignored if useSystemTime is enabled. Default to False.

  • useSystemTime (bool): If True, system timestamp will be included in messages. If False, simulation timestamp will be included in messages. Default to False.

  • frameSkipCount (uint): Specifies the number of simulation frames to skip between each message publish. (e.g. Set to 0 to publish each frame. Set 1 to publish every other frame). Default to 0.

ROS2PublishCameraInfo

[‘This node publishes camera info as a ROS2 CameraInfo message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_camera.

  • topicName (string): Name of ROS2 Topic. Default to camera_info.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • width (uint): Width for output image.

  • height (uint): Height for output image.

  • projectionType (token): projection type.

  • k (double[]): 3x3 Intrinsic camera matrix for the raw (distorted) images. Projects 3D points in the camera coordinate frame to 2D pixel coordinates using the focal lengths and principal point.

  • r (double[]): 3x3 Rectification matrix (stereo cameras only). A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.

  • p (double[]): 3x4 Rectification matrix (stereo cameras only). A rotation matrix aligning the camera coordinate system to the ideal stereo image plane so that epipolar lines in both stereo images are parallel.

  • physicalDistortionModel (token): physical distortion model used for approximation, if blank projectionType is used.

  • physicalDistortionCoefficients (float[]): physical distortion model used for approximation, physicalDistortionModel must be set to use these coefficients.

ROS2SubscribeTwist

[‘This node subscribes to a ROS2 Twist message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to cmd_vel.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

  • linearVelocity (vectord[3]): Linear velocity vector in m/s.

  • angularVelocity (vectord[3]): Angular velocity vector in rad/s.

ROS2ServicePrim

[‘This node provides the services to list prims and all their attributes, as well as read and write a specific attribute’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any service name by the node namespace.

  • primsServiceName (string): Name of the ROS2 service to list all prims in the current stage. Default to get_prims.

  • getAttributesServiceName (string): Name of the ROS2 service to list all specific prim’s attributes. Default to get_prim_attributes.

  • getAttributeServiceName (string): Name of the ROS2 service to read a specific prim attribute. Default to get_prim_attribute.

  • setAttributeServiceName (string): Name of the ROS2 service to write a specific prim attribute. Default to set_prim_attribute.

  • qosProfile (string): QoS profile config.

Outputs
  • execOut (execution): Output execution triggers when a response has been submitted.

ROS2SubscribeAckermannDrive

[‘This node subscribes to a ROS2 AckermannDriveStamped message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to ackermann_cmd.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

  • frameId (string): FrameId for ROS2 message.

  • timeStamp (double): Timestamp of message in seconds.

  • steeringAngle (double): Desired virtual angle in radians. Corresponds to the yaw of a virtual wheel located at the center of the front axle.

  • steeringAngleVelocity (double): Desired rate of change of virtual angle in rad/s. Corresponds to the yaw of a virtual wheel located at the center of the front axle.

  • speed (double): Desired forward speed in m/s.

  • acceleration (double): Desired acceleration in m/s^2.

  • jerk (double): Desired jerk in m/s^3.

ROS2SubscribeTransformTree

[‘This node subscribes to a ROS2 Transform Tree’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to tf.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • frameNamesMap (token[]): Array of [prim_path_0, frame_name_0, prim_path_1, frame_name_1, …]. Default to [].

  • articulationRoots (token[]): Array of articulation root prims that will be modified. Default to [].

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

OgnROS2ServiceClient

[‘This node is a generic service client that provides interface for a ROS service. The request/response fields of the service are parsed and are made accessible via the node based on the service specified from messagePackage, messageSubfolder, messageName. The client sends a request (commanded from the node inputs) and receives a response (accessible from the node outputs) from the server.’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Name of ROS2 Node, prepends any topic published/subscribed by the node name.

  • serviceName (string): Name of ROS2 Service. Default to /service_name.

  • messagePackage (string): Package name (e.g.: example_interfaces for example_interfaces/srv/AddTwoInts).

  • messageSubfolder (string): Subfolder name (e.g.: srv for example_interfaces/srv/AddTwoInts). Default to srv.

  • messageName (string): Service name (e.g.: AddTwoInts for example_interfaces/srv/AddTwoInts).

  • qosProfile (string): QoS profile config.

Outputs
  • execOut (execution): Output execution triggers when the response is received.

ROS2Subscriber

[‘This node subscribes to any existing ROS2 message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to topic.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • messagePackage (string): Message package (e.g.: std_msgs for std_msgs/msg/Int32).

  • messageSubfolder (string): Message subfolder (e.g.: msg for std_msgs/msg/Int32). Default to msg.

  • messageName (string): Message name (e.g.: Int32 for std_msgs/msg/Int32).

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

ROS2PublishBbox3D

[‘This node publishes ROS2 Bbox3d messages’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_camera.

  • topicName (string): Name of ROS2 Topic. Default to bbox3d.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): Time in seconds to use when publishing the message. Default to 0.0.

  • data (uchar[]): Buffer array data. Default to [].

ROS2SubscribeJointState

[‘This node subscribes to a joint state command of a robot in a ROS2 JointState message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to joint_command.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

  • timeStamp (double): ROS2 Timestamp in seconds.

  • jointNames (token[]): Commanded joint names.

  • positionCommand (double[]): Position commands.

  • velocityCommand (double[]): Velocity commands.

  • effortCommand (double[]): Effort commands.

ROS2PublishPointCloud

[‘This node publishes LiDAR scans as a ROS2 PointCloud2 message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_lidar.

  • topicName (string): Name of ROS2 Topic. Default to point_cloud.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • dataPtr (uint64): Pointer to the buffer data. Default to 0.

  • data (pointf[3][]): Buffer array data, must contain data if dataPtr is null. Default to [].

  • cudaDeviceIndex (int): Index of the device where the data lives (-1 for host data). Default to -1.

  • bufferSize (uint): Size (in bytes) of the buffer (0 if the input is a texture).

ROS2PublishLaserScan

[‘This node publishes LiDAR scans as a ROS2 LaserScan message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_lidar.

  • topicName (string): Name of ROS2 Topic. Default to scan.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • horizontalFov (float): Horizontal Field of View (deg). Default to 0.

  • horizontalResolution (float): Increment between horizontal rays (deg). Default to 0.

  • depthRange (float[2]): Range for sensor to detect a hit [min, max] (m). Default to [0, 0].

  • rotationRate (float): Rotation rate of sensor in Hz. Default to 0.

  • linearDepthData (float[]): Linear depth measurements from full scan, ordered by increasing azimuth (m). Default to [].

  • intensitiesData (uchar[]): Intensity measurements from full scan, ordered by increasing azimuth. Default to [].

  • numRows (int): Number of rows in buffers. Default to 0.

  • numCols (int): Number of columns in buffers. Default to 0.

  • azimuthRange (float[2]): The azimuth range [min, max] (deg). Always [-180, 180] for rotary lidars. Default to [0.0, 0.0].

ROS2PublishAckermannDrive

[‘This node subscribes to a ROS2 AckermannDriveStamped message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to ackermann_cmd.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • frameId (string): FrameId for ROS2 message.

  • timeStamp (double): Timestamp of message in seconds. Default to 0.

  • steeringAngle (double): Desired virtual angle in radians. Corresponds to the yaw of a virtual wheel located at the center of the front axle. Default to 0.0.

  • steeringAngleVelocity (double): Desired rate of change of virtual angle in rad/s. Corresponds to the yaw of a virtual wheel located at the center of the front axle. Default to 0.0.

  • speed (double): Desired forward speed in m/s. Default to 0.0.

  • acceleration (double): Desired acceleration in m/s^2. Default to 0.0.

  • jerk (double): Desired jerk in m/s^3. Default to 0.0.

ROS2PublishSemanticLabels

[‘This node publishes ROS2 semantic label messages’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to labels.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): Time in seconds to use when publishing the message. Default to 0.0.

  • ids (uint[]): Unoccluded semantic u ids (or color, if colorize is set to True).

  • labels (token[]): Prim path of the prim.

  • semantics (token[]): Semantic labels that correspeond to the ids.

  • idToLabels (string): Mapping from id to semantic labels.

ROS2SubscribeClock

[‘This node subscribes to a ROS2 Clock message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to clock.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

Outputs
  • execOut (execution): Output execution triggers when a new message is received.

  • timeStamp (double): Time in seconds.

ROS2PublishClock

[‘This node publishes the given time as a ROS2 Clock message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to clock.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): Time in seconds to use when publishing the message. Default to 0.

OgnROS2ServiceServerResponse

[‘This node is a generic service server that provides interface for a ROS service. The response fields of the service are parsed and are made accessible via the node based on the service specified from messagePackage, messageSubfolder, messageName. The server sends a response (commanded from the node inputs) to the client. This node can only receive the requests, and should be connected to a OgnROS2ServiceServerRequest through the out serverHandle parameter in order to send a response.’]

Inputs
  • onReceived (execution): The input execution port when a request is received.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Name of ROS2 Node, prepends any topic published/subscribed by the node name.

  • serverHandle (uint64): handle to the server. Default to 0.

  • messagePackage (string): Package name (e.g.: example_interfaces for example_interfaces/srv/AddTwoInts).

  • messageSubfolder (string): Subfolder name (e.g.: srv for example_interfaces/srv/AddTwoInts). Default to srv.

  • messageName (string): Service name (e.g.: AddTwoInts for example_interfaces/srv/AddTwoInts).

Outputs
  • execOut (execution): Output execution triggers when a response is sent.

ROS2PublishJointState

[‘This node publishes joint states of a robot in ROS2 JointState message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • targetPrim (target): USD reference to the robot prim.

  • nodeNamespace (string): Name of ROS2 Node, prepends any topic published/subscribed by the node name.

  • topicName (string): Name of ROS2 Topic. Default to joint_states.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

ROS2Publisher

[‘This node publishes any existing ROS2 message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to topic.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • messagePackage (string): Message package (e.g.: std_msgs for std_msgs/msg/Int32).

  • messageSubfolder (string): Message subfolder (e.g.: msg for std_msgs/msg/Int32). Default to msg.

  • messageName (string): Message name (e.g.: Int32 for std_msgs/msg/Int32).

Outputs
  • execOut (execution): Output execution triggers when a new message is published.

ROS2PublishImu

[‘This node publishes IMU data as a ROS2 IMU message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_imu.

  • topicName (string): Name of ROS2 Topic. Default to imu.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • publishOrientation (bool): Include orientation in msg. Default to True.

  • publishLinearAcceleration (bool): Include Linear acceleration in msg. Default to True.

  • publishAngularVelocity (bool): Include Angular velocity in msg. Default to True.

  • orientation (quatd[4], optional): Orientation as a quaternion (IJKR). Default to [0.0, 0.0, 0.0, 1.0].

  • linearAcceleration (vectord[3], optional): Linear acceleration vector in m/s^2. Default to [0.0, 0.0, 0.0].

  • angularVelocity (vectord[3], optional): Angular velocity vector in rad/s. Default to [0.0, 0.0, 0.0].

ROS2PublishOdometry

[‘This node publishes odometry as a ROS2 Odometry message’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • odomFrameId (string): FrameId for ROS2 odometry message. Default to odom.

  • chassisFrameId (string): FrameId for robot chassis frame. Default to base_link.

  • topicName (string): Name of ROS2 Topic. Default to odom.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • position (vectord[3]): Position vector in meters. Default to [0.0, 0.0, 0.0].

  • orientation (quatd[4]): Orientation as a quaternion (IJKR). Default to [0.0, 0.0, 0.0, 1.0].

  • linearVelocity (vectord[3]): Linear velocity vector in m/s. Default to [0.0, 0.0, 0.0].

  • angularVelocity (vectord[3]): Angular velocity vector in rad/s. Default to [0.0, 0.0, 0.0].

  • robotFront (vectord[3]): The front of the robot. Default to [1.0, 0.0, 0.0].

ROS2PublishBbox2D

[‘This node publishes ROS2 Bbox2d messages’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_camera.

  • topicName (string): Name of ROS2 Topic. Default to bbox2d.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): Time in seconds to use when publishing the message. Default to 0.0.

  • data (uchar[]): Buffer array data. Default to [].

OgnROS2ServiceServerRequest

[‘This node is a generic service server that provides interface for a ROS service. The request/response fields of the service are parsed and are made accessible via the node based on the service specified from messagePackage, messageSubfolder, messageName. The server receives a request (accessible from the node outputs). To receive the response this node should be connected to a OgnROS2ServiceServerResponse node through the serverHandle input. The OgnROS2ServiceServerResponse node is responsible for providing the response.’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Name of ROS2 Node, prepends any topic published/subscribed by the node name.

  • serviceName (string): Name of ROS2 Service. Default to /service_name.

  • messagePackage (string): Package name (e.g.: example_interfaces for example_interfaces/srv/AddTwoInts).

  • messageSubfolder (string): Subfolder name (e.g.: srv for example_interfaces/srv/AddTwoInts). Default to srv.

  • messageName (string): Service name (e.g.: AddTwoInts for example_interfaces/srv/AddTwoInts).

  • qosProfile (string): QoS profile config.

Outputs
  • onReceived (execution): Output execution triggers when a request is received.

  • serverHandle (uint64): handle to the server.

ROS2PublishTransformTree

[‘This node publishes the pose of prims as a ROS2 Transform Tree’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • parentPrim (target, optional): Prim used as parent frame for poses, leave blank to use World.

  • targetPrims (target): Target prims to publish poses for, if prim is an articulation, the entire articulation tree will be published.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • topicName (string): Name of ROS2 Topic. Default to tf.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • staticPublisher (bool): If enabled this will override QoS settings to publish static transform trees, similar to tf2::StaticTransformBroadcaster. Default to False.

ROS2PublishRawTransformTree

[‘This node publishes a user-defined transformation between any two coordinate frames as a ROS2 Transform Tree’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • parentFrameId (string): Parent frameId for ROS2 TF message. Default to odom.

  • childFrameId (string): Child frameId for ROS2 TF message. Default to base_link.

  • topicName (string): Name of ROS2 Topic. Default to tf.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): ROS2 Timestamp in seconds. Default to 0.0.

  • translation (vectord[3]): Translation vector in meters. Default to [0.0, 0.0, 0.0].

  • rotation (quatd[4]): Rotation as a quaternion (IJKR). Default to [0.0, 0.0, 0.0, 1.0].

  • staticPublisher (bool): If enabled this will override QoS settings to publish static transform trees, similar to tf2::StaticTransformBroadcaster. Default to False.

ROS2Context

[‘This node creates a ROS2 Context for a given domain ID’]

Inputs
  • domain_id (uchar): Domain ID for ROS context. Default to 0.

  • useDomainIDEnvVar (bool): Set to true to use ROS_DOMAIN_ID environment variable if set. Defaults to domain_id if not found. Default to True.

Outputs
  • context (uint64): handle to initialized ROS2 context.

ROS2PublishImage

[‘This node publishes ROS2 Image messages’]

Inputs
  • execIn (execution): The input execution port.

  • context (uint64): ROS2 context handle, Default of zero will use the default global context. Default to 0.

  • nodeNamespace (string): Namespace of ROS2 Node, prepends any published/subscribed topic by the node namespace.

  • frameId (string): FrameId for ROS2 message. Default to sim_camera.

  • topicName (string): Name of ROS2 Topic. Default to rgb.

  • qosProfile (string): QoS profile config.

  • queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Only honored if ‘history’ QoS policy was set to ‘keep last’. This setting can be overwritten by qosProfile input. Default to 10.

  • timeStamp (double): Time in seconds to use when publishing the message. Default to 0.0.

  • data (uchar[]): Buffer array data. Default to [].

  • width (uint): Buffer array width. Default to 0.

  • height (uint): Buffer array height. Default to 0.

  • encoding (token): ROS encoding format for the input data, taken from the list of strings in include/sensor_msgs/image_encodings.h. Input data is expected to already be in this format, no conversions are performed. Default to rgb8.

  • dataPtr (uint64): Pointer to the raw rgba array data. Default to 0.

  • cudaDeviceIndex (int): Index of the device where the data lives (-1 for host data). Default to -1.

  • bufferSize (uint): Size (in bytes) of the buffer (0 if the input is a texture).

  • format (uint64): Format.