Contenu principal

Use ROS Bridge to Establish Communication Between ROS and ROS 2

ROS 2 is newer version of ROS with different architecture. Both the networks are separate and there is no direct communication between the nodes in ROS and ROS 2. The ros1_bridge package provides a network bridge which enables the exchange of messages between ROS and ROS 2. The bridge manages all the conversion required and sends messages across both the networks. For more information, see ros1_bridge. This example uses a virtual machine which may be downloaded by following the instructions in Get Started with Gazebo and Simulated TurtleBot. The ros1_bridge package is installed on this virtual machine.

This example shows how to control the TurtleBot3 in Gazebo using keyboard commands from the MATLAB®. The Gazebo Simulator is available in ROS 1 networks only. You can use ros1_bridge to exchange the Gazebo topics such as '/odom' or '/cmd_vel' to ROS 2.

The below diagram depicts the message exchange between ROS 1 and ROS 2 networks using ros1_bridge. The '/odom' topic contains nav_msgs/Odometry messages sent from the ROS 1 network with Gazebo. The ROS 2 node subscribes to the /odom topic that has been bridged from ROS 1 and publishes a '/cmd_vel' message based on the robot pose. The bridge then takes the '/cmd_vel' message and publishes it on the ROS 1 network.

ROS and ROS 2 connection workflow using ROS Bridge

Prerequisites:

Set Up Virtual Machine

Communicate Outside Subnet

Open the DEFAULT_FASTRTPS_PROFILE.xml file in the home directory of the VM and replace <address> entries with host and VM IP addresses. To communicate under different subnets (see Communicate Outside Subnet section in Connect to a ROS 2 Network).

Virtual machine setup to communicate outside subnet

Launch Gazebo

On the VM desktop, click Gazebo Empty. This Gazebo world contains a Turtlebot robot, which publishes and subscribes to messages on a ROS 1 network.

Gazebo world in virtual machine

Start the Bridge

Click the ROS Bridge shortcut. This bridge setups publishers and subscribers for all the ROS 1 topics on a ROS 2 network.

ROS Toolbox virtual machine for Gazebo world

In the Terminal window, notice that the bridge is up and running.

ROS Toolbox virtual machine terminal window

Open one more terminal and enter the following commands

export ROS_DOMAIN_ID=25
source /opt/ros/foxy/setup.bash

Now check that Gazebo topics are present in ROS 2.

ros2 topic list

ROS Toolbox virtual machine terminal window

Echo the /odom topic to see messages being published.

ros2 topic echo /odom

ROS Toolbox virtual machine terminal window

Control the TurtleBot3 from ROS 2

In MATLAB on your host machine, set the proper domain ID for the ROS 2 network using the 'ROS_DOMAIN_ID' environment variable to 25 to match the robot simulator ROS bridge settings and run ros2 topic list to verify that the topics from the robot simulator are visible in MATLAB.

setenv("ROS_DOMAIN_ID","25");
ros2 topic list
/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/performance_metrics
/imu
/joint_states
/odom
/parameter_events
/rosout
/rosout_agg
/scan
/tf

Create a ROS 2 node. Subscribe to the odometry topic that is bridged from ROS 1.

ros2Node = ros2node("/example_node");
handles.odomSub = ros2subscriber(ros2Node,"/odom","nav_msgs/Odometry")
handles = struct with fields:
    odomSub: [1×1 ros2subscriber]

Receive the odometry messages from the bridge and use the exampleHelperGet2DPose function to unpack the message into a 2D pose. Get the start position of the robot.

odomMsg = receive(handles.odomSub);
poseStart = exampleHelperGet2DPose(odomMsg)
poseStart = 1×3
10-3 ×

   -0.0256    0.0374    0.5800

handles.poses = poseStart;

Create a publisher for controlling the robot velocity. The bridge takes these messages and sends them on the ROS 1 network.

handles.velPub = ros2publisher(ros2Node,'/cmd_vel','geometry_msgs/Twist')
handles = struct with fields:
    odomSub: [1×1 ros2subscriber]
      poses: [-2.5609e-05 3.7370e-05 5.7996e-04]
     velPub: [1×1 ros2publisher]

Run the exampleHelperROS2TurtleBotKeyboardControl function, which allows you to control the TurtleBot3 with the keyboard. The handles input contains the ROS 2 subscriber, ROS 2 publisher, and poses as a structure. The function sends control commands on the ROS 2 network based on the keyboard inputs. The bridge transfers those messages to the ROS 1 network for the Gazebo simulator.

poses = exampleHelperROS2TurtleBotKeyboardControl(handles);

The figure that opens listens to keyboard inputs for controlling the robot in Gazebo. Hit the keys and watch the robot move. Press Q to exit.

Keyboard inputs for controlling the robot in GazeboRobot simulation in Gazebo world

Plot Data Received from ROS

Plot the results to show how TurtleBot3 moved in Gazebo. The poses variable has stored all the updated /odom messages that were received from the ROS 1 network.

odomMsg = receive(handles.odomSub);
poseEnd = exampleHelperGet2DPose(odomMsg)
poseEnd = 1×3

    0.8522    0.1618   -1.6255

poses = [poses;poseEnd];
figure
plot(poses(:,1),poses(:,2),'b-', ... 
     poseStart(1),poseStart(2),'go', ...
     poseEnd(1),poseEnd(2),'ro');
xlabel('X [m]');
ylabel('Y [m]');
legend('Trajectory','Start','End');

Clear the publishers and subscribers on the host.

clear