Main Content

Control NVIDIA Carter Robot in Isaac Sim Using ROS 2

In this example, you publish ROS 2 messages from MATLAB to the Carter robot in NVIDIA Isaac Sim® application. You also subscribe to the topics that the Carter robot publishes in MATLAB, such as odometry, image, and camera data. This example was tested using Isaac Sim version 2022.2.1 on a Windows® platform.

To set up and launch the NVIDIA Isaac Sim® from MATLAB® through a ROS 2 interface, see Set Up and Connect to NVIDIA Isaac Sim.

Get Started with Carter Robot Interaction from MATLAB

To get started after setting up NVIDIA Isaac Sim by following the steps outlined in Set Up and Connect to NVIDIA Isaac Sim, create a node in MATLAB. This action starts the ROS 2 network automatically.

node = ros2node("carterNode");

Query available topics in the ROS 2 network. Ensure that the warehouse scene is playing in NVIDIA Isaac Sim to see the topics that the Carter robot publishes.

ros2 topic list
/camera_info_left
/clock
/cmd_vel
/odom
/parameter_events
/rgb_left
/rosout
/scan
/tf

You can control the movement of the Carter robot by publishing a message to the /cmd_vel topic. The message must have the type geometry_msgs/Twist, which contains data specifying the linear and angular velocities. The linear velocity along the x-axis controls forward and backward motion. The angular velocity around the z-axis controls the rotation speed of the robot base.

Specify the velocity in m/s.

velocity = 0.1;

Create a ROS 2 publisher for the /cmd_vel topic and the corresponding message containing the velocity values.

robotCmd = ros2publisher(node,"/cmd_vel");
velMsg = ros2message(robotCmd);

Set the forward velocity of the robot using the velocity variable and publish the command to the robot. Let the robot move for a moment, and then bring it to a stop.

velMsg.angular.z = 0;
velMsg.linear.x = velocity;
send(robotCmd,velMsg)
pause(4)
velMsg.linear.x = 0;
send(robotCmd,velMsg)

Receive Robot Position and Orientation

The Carter robot uses the /odom topic to publish its current position and orientation (collectively referred to as pose). Because the Carter robot is not equipped with a global positioning system (GPS) system, the pose is relative to the initial pose of the robot.

Create a ROS 2 subscriber for the odometry messages

odomSub = ros2subscriber(node,"/odom");

Wait for the subscriber to return data, then extract the data and assign it to variables x, y, and z. If the software returns an error, then the receive command likely timed out. Ensure that the robot is publishing odometry and that your network is configured properly.

odomMsg = receive(odomSub,3);
pose = odomMsg.pose.pose;
x = pose.position.x;
y = pose.position.y;
z = pose.position.z;

Display the position of the robot.

[x y z]
ans = 1×3

    0.3959   -0.0000    0.0016

The pose object stores the orientation of the Carter robot as a quaternion in the Orientation property. Use quat2eul (Robotics System Toolbox) to convert the orientation to the more convenient representation of Euler angles. Display the current orientation, theta, of the robot in degrees.

quat = pose.orientation;
angles = quat2eul([quat.w quat.x quat.y quat.z]);
theta = rad2deg(angles(1))
theta = -0.0037

Receive Camera Data

Subscribe to the /rgb_left topic, on which the Carter robot publishes the camera RGB images.

cameraSub = ros2subscriber(node,"/rgb_left");

Wait for the image data, convert the received ROS 2 message into image matrix using rosReadImage, and then display the result by using imshow.

cameraMsg = receive(cameraSub);
I = rosReadImage(cameraMsg);
imshow(I)

Display continuously updating camera data while the Carter robot turns for a short duration.

velMsg.angular.z = velocity;
send(robotCmd,velMsg);
tic;
while toc < 20
  imgMsg = receive(cameraSub);
  I = rosReadImage(imgMsg);
  imshow(I)
  drawnow
end

Set the angular velocity of the robot to 0 and publish the command to the robot, for it to stop rotating.

velMsg.angular.z = 0;
send(robotCmd,velMsg);

Receive Lidar Data

Subscribe to the /scan topic on which the Carter robot publishes lidar data.

lidarSub = ros2subscriber(node,"/scan");

Wait for the data and then display it with rosPlot.

scanMsg = receive(lidarSub);
figure
rosPlot(scanMsg)

Continuously display updating lidar scans while the Carter robot turns for a short duration.

velMsg.angular.z = velocity;
send(robotCmd,velMsg)
tic
while toc < 20
  scanMsg = receive(lidarSub);
  rosPlot(scanMsg)
end

Set the angular velocity of the robot to 0 and publish the command to the robot, for it to stop rotating.

velMsg.angular.z = 0;
send(robotCmd,velMsg)