ROS Bridge [omni.isaac.ros_bridge]
Acquiring Extension Interface
- _ros_bridge.acquire_ros_bridge_interface(plugin_name: str = None, library_path: str = None) omni.isaac.ros_bridge._ros_bridge.RosBridge
- _ros_bridge.release_ros_bridge_interface(arg0: omni.isaac.ros_bridge._ros_bridge.RosBridge) None
ROS Bridge API
- class RosBridge
Omnigraph Nodes
ROS1RtxLidarHelper
Handles automation of Lidar Sensor pipeline
- Inputs
execIn (execution): Triggering this causes the sesnor pipeline to be generated.
enabled (bool): True to enable the lidar helper, False to disable. Default to True.
nodeNamespace (string): Namespace of ROS1 Node, prepends and published/subscribed topic by the node namespace.
frameId (string): FrameID for the ROS1 message, the node namespace will be prefixed to the frame id. Default to sim_lidar.
topicName (string): Topic name for sensor data. Default to scan.
queueSize (uint64): Number of message to queue up before throwing away, in case messages are collected faster than they can be sent. Default to 10.
renderProductPath (token): Name of the render product path to publish lidar data.
type (token): Data to publsih 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.
ROS1CameraHelper
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.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message, the nodeNamespace will be prefixed to the frame id. Default to sim_camera.
topicName (string): Topic name for sensor data. Default to rgb.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. 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.
ROS1ServiceTeleport
[‘This node provides the service to teleport a robot to the commanded pose’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
serviceName (string): Name of ROS1 service. Default to teleport.
ROS1SubscribeTwist
[‘This node subscribes to a ROS1 Twist message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to cmd_vel.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. 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.
ROS1PublishTransformTree
[‘This node publishes the pose of prims as a ROS1 Transform Tree’]
- Inputs
execIn (execution): The input execution port.
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 ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to /tf.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 Timestamp in seconds. Default to 0.0.
ROS1PublishOdometry
[‘This node publishes odometry as a ROS1 Odometry message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
odomFrameId (string): FrameId for ROS1 odometry message. Default to odom.
chassisFrameId (string): FrameId for robot chassis frame. Default to base_link.
topicName (string): Name of ROS1 Topic. Default to odom.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 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].
ROS1PublishSemanticLabels
[‘This node publishes ROS1 semantic label messages’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to labels.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. 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.
ROS1Master
[‘This node provides the current status of the ROS master node’]
- Inputs
execIn (execution): The input execution port.
- Outputs
status (bool): Check whether the master is up.
host (string): The master’s hostname, as a string.
port (uint): The master’s port.
uri (string): RGet the full URI to the master (eg. http://host:port/).
ROS1SubscribeAckermannDrive
[‘This node subscribes to a ROS1 AckermannDriveStamped message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to ackermann_cmd.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Default to 10.
- Outputs
execOut (execution): Output execution triggers when a new message is received.
frameId (string): FrameId for ROS1 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.
ROS1PublishJointState
[‘This node publishes joint states of a robot in ROS1 JointState message’]
- Inputs
execIn (execution): The input execution port.
targetPrim (target): USD reference to the robot prim.
nodeNamespace (string): Name of ROS1 Node, prepends any topic published/subscribed by the node name.
topicName (string): Name of ROS1 Topic. Default to joint_states.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 Timestamp in seconds. Default to 0.0.
ROS1PublishBbox3D
[‘This node publishes ROS1 Bbox3d messages’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_camera.
topicName (string): Name of ROS1 Topic. Default to bbox3d.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. 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 [].
ROS1PublishClock
[‘This node publishes the given time as a ROS1 Clock message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to clock.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): Time in seconds to use when publishing the message. Default to 0.
ROS1PublishImage
[‘This node publishes ROS1 Image messages’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_camera.
topicName (string): Name of ROS1 Topic. Default to rgb.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. 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.
ROS1SubscribeClock
[‘This node subscribes to a ROS1 Clock message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to clock.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Default to 10.
- Outputs
execOut (execution): Output execution triggers when a new message is received.
timeStamp (double): Time in seconds.
ROS1PublishPointCloud
[‘This node publishes LiDAR scans as a ROS1 PointCloud2 message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_lidar.
topicName (string): Name of ROS1 Topic. Default to point_cloud.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 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).
ROS1PublishAckermannDrive
[‘This node subscribes to a ROS1 AckermannDriveStamped message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to ackermann_cmd.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be processed. Default to 10.
frameId (string): FrameId for ROS1 message.
timeStamp (double): Timestamp of message in seconds. Default to 0.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.
ROS1PublishBbox2D
[‘This node publishes ROS1 Bbox2d messages’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_camera.
topicName (string): Name of ROS1 Topic. Default to bbox2d.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. 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 [].
ROS1PublishLaserScan
[‘This node publishes LiDAR scans as a ROS1 LaserScan message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_lidar.
topicName (string): Name of ROS1 Topic. Default to scan.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 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].
ROS1PublishImu
[‘This node publishes IMU data as a ROS1 IMU message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_imu.
topicName (string): Name of ROS1 Topic. Default to imu.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 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].
ROS1PublishRawTransformTree
[‘This node publishes a user-defined transformation between any two coordinate frames as a ROS1 Transform Tree’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
parentFrameId (string): Parent frameId for ROS1 TF message. Default to odom.
childFrameId (string): Child frameId for ROS1 TF message. Default to base_link.
topicName (string): Name of ROS1 Topic. Default to /tf.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 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].
ROS1SubscribeJointState
[‘This node subscribes to a joint state command of a robot in a ROS1 JointState message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
topicName (string): Name of ROS1 Topic. Default to joint_command.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
- Outputs
execOut (execution): Output execution triggers when a new message is received.
timeStamp (double): ROS1 Timestamp in seconds.
jointNames (token[]): Commanded joint names.
positionCommand (double[]): Position commands.
velocityCommand (double[]): Velocity commands.
effortCommand (double[]): Effort commands.
ROS1PublishCameraInfo
[‘This node publishes camera info as a ROS1 CameraInfo message’]
- Inputs
execIn (execution): The input execution port.
nodeNamespace (string): Namespace of ROS1 Node, prepends any published/subscribed topic by the node namespace.
frameId (string): FrameId for ROS1 message. Default to sim_camera.
topicName (string): Name of ROS1 Topic. Default to camera_info.
queueSize (uint64): The number of messages to queue up before throwing some away, in case messages are collected faster than they can be sent. Default to 10.
timeStamp (double): ROS1 Timestamp in seconds. Default to 0.0.
width (uint): Width for output image.
height (uint): Height for output image.
focalLength (float): focal length.
horizontalAperture (float): horizontal aperture.
verticalAperture (float): vertical aperture.
horizontalOffset (float): horizontal offset.
verticalOffset (float): vertical offset.
projectionType (token): projection type.
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, 0.0].
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.