Main Content

Connect to a ROS-Enabled Robot from Simulink over ROS 2

This example shows you how to configure a Simulink® model to send and receive information from a separate ROS-based simulator such as Gazebo® over ROS 2.

Introduction

You can use Simulink to connect to a ROS-enabled physical robot or to a ROS-enabled robot simulator such as Gazebo. This example shows how to:

  • Configure Simulink to connect to a separate robot simulator using ROS 2

  • Send velocity commands to a simulated robot

  • Receive position information from a simulated robot

Prerequisites

Task 1 - Start a Gazebo Robot Simulator

In this task, you will start a ROS-based simulator for a differential-drive robot along with a ROS bridge that replays ROS messages over ROS 2 network.

  • In the Ubuntu desktop, click the "Gazebo Empty" icon to start the Gazebo world.

  • Click on the "ROS Bridge" icon, to relay messages between ROS and ROS 2 network.

  • 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

The simulator receives and sends messages on the following topics:

  • Receives geometry_msgs/Twist velocity command messages on the /cmd_vel topic.

  • Sends nav_msgs/Odometry messages to the /odom topic.

Open Existing Model

After connecting to the ROS 2 network, open the example model.

open_system('robotROS2ConnectToRobotExample');

Task 2 - Configure Simulink to Connect to the ROS 2 Network

  • From the Simulation tab Prepare gallery, click ROS Network under ROS TOOLBOX.

  • In the Configure ROS Network Addresses dialog, under Domain ID (ROS 2), set ID to 25. This ID value matches the domain ID of the ROS 2 network on the Ubuntu virtual machine, where the messages from Gazebo in ROS network are received.

Task 3 - Send Velocity Commands To the Robot

Create a publisher that sends control commands (linear and angular velocities) to the simulator. Make these velocities adjustable by using Slider Gain blocks.

ROS uses a right-handed coordinate system, so X-axis is forward, Y-axis is left and Z-axis is up. Control commands are sent using a geometry_msgs/Twist message, where linear.x indicates linear forward velocity (in meters/sec), and angular.z indicates angular velocity around the Z-axis (in radians/sec).

  • Open a new Simulink model.

  • On the ROS tab, under CONNECT, click Select a ROS Network and select Robot Operating System 2 (ROS 2).

  • From the ROS Toolbox > ROS 2 tab in the Library Browser, drag a Publish block to the model. Double-click the block.

  • Set Topic source to Specify your own. Enter /cmd_vel in the Topic field. Click Select next to Message Type, select geometry_msgs/Twist from drop down list, and click OK.

  • From the ROS Toolbox > ROS 2 tab in the Library Browser, drop a Blank Message block to the model. Double-click the block.

  • Click Select next to Message type and select geometry_msgs/Twist.

  • Set Sample time to 0.01 and click OK.

  • From the Simulink > Signal Routing tab in the Library Browser, drag a Bus Assignment block to the model.

  • Connect the output of the Blank Message block to the Bus input of the Bus Assignment block, and the Bus output to the input of the Publish block.

  • From the Modeling tab, click Update Model to ensure that the bus information is correctly propagated. Ignore the error, "Selected signal 'signal1' in the Bus Assignment block 'untitled/Bus Assignment' cannot be found in the input bus signal", if it appears. The next step will resolve this error.

  • Double-click the Bus Assignment block. Select ??? signal1 in the right listbox and click Remove. In the left listbox, expand both linear and angular properties. Select linear > x and angular > z and click Select. Click OK to close the block mask.

  • Add a Constant block, a Gain block, and two Slider Gain blocks. Connect them together as shown in picture below, and set the Gain value to -1.

  • Set the limits, and current parameters of the linear velocity slider to 0.0 to 2.0, and 1.0 respectively. Set the corresponding parameters of the steering gain slider to -1.0 to 1.0, and 0.1.

Task 4 - Receive Location Information From the Robot

Create a subscriber to receive messages sent to the /odom topic. You will also extract the location of the robot and plot its path in the XY-plane.

  • From the ROS Toolbox > ROS 2 tab in the Library Browser, drag a Subscribe block to the model. Double-click the block.

  • Set Topic source to Select From ROS network, and click Select next to the Topic box. Select "/odom" for the topic and click OK. Note that the message type nav_msgs/Odometry is set automatically.

  • From the Simulink > Signal Routing tab in the Library Browser, drag a Bus Selector block to the model.

  • Connect the Msg output port of the Subscribe block to the input port of the Bus Selector block. In the Modeling tab, click Update Model to ensure that the bus information is correctly propagated.

  • Double-click the Bus Selector block. Select signal1 and signal2 in the right listbox and click to remove them. In the left listbox, expand pose > pose > position and select x and y. Click to select the signals and then OK.

  • From the Simulink > Sinks tab in the Library Browser, drag an XY Graph block to the model. Connect the X and Y output ports of the Bus Selector block to the input ports of the XY Graph block.

The following figure shows the completed model. A pre-configured model is included for your convenience.

Task 5 - Configure and Run the Model

  • From the Modeling tab, click Model Settings. In the Solver pane, set Type to Fixed-step and Fixed-step size to 0.01.

  • Set simulation Stop time to inf.

  • Click Run to start the simulation.

  • In both the simulator and XY plot, you should see the robot moving in a circle.

  • While the simulation is running, change the values of Slider Gain blocks to control the robot. Double-click the XY Graph block and change the X and Y axis limits if needed (you can do this while the simulation is running).

  • To stop the simulation, click Stop.