Connect to a ROS-enabled Robot from Simulink
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. It then shows how to send velocity commands and receive position information from a simulated robot.
You can follow the steps in the example to create your own model, or you can use this completed version instead.
open_system('robotROSConnectToRobotExample');
Prerequisites: Get Started with ROS, Exchange Data with ROS Publishers and Subscribers, Get Started with ROS in Simulink.
Robot Simulator
Start a ROS-based simulator for a differential-drive robot. The simulator receives and sends messages on the following topics:
Sends
nav_msgs/Odometry
messages to the/odom
topicReceives
geometry_msgs/Twist
velocity command messages on the /mobile_base/commands
or/cmd_vel
topic, based on the ROS-based simulator
You can choose one of two options for setting up the ROS-based simulator.
Option A: Simulator in MATLAB®
Use a simple MATLAB-based simulator to plot the current location of the robot in a separate figure window.
Enter
rosinit
at the MATLAB command line. This creates a local ROS master with network address (URI) ofhttp://localhost:11311
.Enter
ExampleHelperSimulinkRobotROS
to start the Robot Simulator:
Note: The
geometry_msgs/Twist
velocity command messages are received on the /mobile_base/commands/velocity
topic.
Option B: Gazebo Simulator
Use a simulated TurtleBot® in Gazebo.
See Add, Build, and Remove Objects in Gazebo for instructions on setting up the Gazebo environment. In the Ubuntu® desktop in the virtual machine, click the "Gazebo Empty" icon.
Note the network address (URI) of the ROS master. It will look like
http://192.168.84.128:11311
, but with your specific IP address.Verify that the Gazebo environment is properly set up by typing the
rostopic
list
in the Ubuntu terminal window. You should see a list of topics, including/cmd_vel
and/odom
.Note: The
geometry_msgs/Twist
velocity command messages are received on the /cmd_vel topic.
Configure Simulink to Connect to the ROS Network
1. From the Simulation tab, select ROS Toolbox > ROS Network.
2. In the ROS Master (ROS 1) section, select Custom
from the Network Address dropdown.
Option A (MATLAB Simulator): Ensure that the Hostname/IP Address is set to
localhost
, and Port is set to11311
.Option B (Gazebo Simulator): Specify the IP address and port number of the ROS master in Gazebo. For example, if it is
http://192.168.60.165:11311
, then enter192.168.60.165
in the Hostname/IP address box and11311
in the Port box.
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 m/s), and Angular.Z
indicates angular velocity around the Z-axis (in rad/s).
Configure a Publisher Block
Open a new Simulink model.
From the ROS Toolbox > ROS tab in the Library Browser, drag a Publish block to the model. Double-click the block.
Set Topic source field to
Select From ROS network
. Select a topic based on the simulator as shown below.
Option A (MATLAB Simulator): Click Select next to Topic, select
/mobile_base/commands/velocity
, and click OK. Note that the message type (geometry_msgs/Twist
) is set automatically.Option B (Gazebo Simulator): Click Select next to Topic, select
/cmd_vel
, and click OK. Note that the message type (geometry_msgs/Twist
) is set automatically.
Configure a Message Block
From the ROS Toolbox > ROS 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.
Configure Message Inputs
From the Simulink > Signal Routing tab in the Library Browser, drag a Bus Assignment block to the model.
Connect the
Msg
output of the Blank Message block to theBus
input of the Bus Assignment block, and theBus
output to theMsg
input of the Publish block.Double-click the Bus Assignment block.
In the list of elements in the bus, expand both
Linear
andAngular
. SelectLinear
>X
andAngular
>Z
. Then, click Select. If these elements are not listed as elements of the input bus, close the dialog box. To ensure that the bus information is propagated, on the Modeling tab, click Update Model. Then, reopen the dialog box.In the list of elements that are being assigned, select
???
signal1
. Then, click Remove.Click OK to close the dialog box.
Add a Constant block, a Gain block, and two Slider Gain blocks. Connect them together as shown in the figure, and set the Gain value to
-1.
Set the limits and current parameters of the linear velocity slider to
0.0
to2.0
, and1.0
respectively. Set the corresponding parameters of the steering gain slider to-1.0
to1.0
, and0.1
.
Receive Location Information from the Robot
Create a subscriber to receive messages sent to the /odom
topic. Extract the location of the robot and plot it's path in the XY-plane.
Configure a Subscriber block
From the ROS Toolbox > ROS 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 typenav_msgs/Odometry
is set automatically.
Read Message Output
From the Simulink > Signal Routing tab in the Library Browser, drag a Bus Selector block to the model.
Connect the output port of the Subscribe block to the input port of the Bus Selector block.
Double-click the Bus Selector block.
In the list of elements in the bus, expand
Pose
>Pose
>Position
and selectX
andY
. To add these elements to the block output, click . If these elements are not listed as elements of the input bus, close the dialog box. To ensure that the bus information is propagated, on the Modeling tab, click Update Model. Then, reopen the dialog box.In the list of output elements, select
signal1
andsignal2
. To remove these elements, click .From the Simulink > Sinks tab in the Library Browser, drag an XY Graph block to the model. Connect the
X
andY
output ports of the Bus Selector block to the input ports of the XY Graph block.
This figure shows the completed model. A pre-configured model is included for your convenience.
Note: The Publisher block in this model uses the /mobile_base/commands/velocity
topic for use with MATLAB simulator option. For Gazebo simulator option, select the /cmd_vel
topic as shown above.
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 to0.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
andY
axis limits if needed. (You can do this while the simulation is running.)To stop the simulation, click Stop.