Generate a Standalone ROS 2 Node
This example shows how to generate C++ code for a standalone ROS 2 node from a MATLAB® function. It then shows how to build and run the ROS 2 node on a Windows® machine.
Prerequisites
To run this example, you require access to:
An Ubuntu Linux system with ROS 2 and an SSH server installed. You can use your own Ubuntu ROS 2 system, or you can use the Linux virtual machine for ROS Toolbox examples. For more information, see Get Started with Gazebo and Simulated TurtleBot.
A C/C++ compiler that is configured properly. You can use the
mex -setup cpp
to view and change the default compiler. For more details, see Change Default Compiler.
Control ROS 2 - Enabled Robot
Open the function robotROS2FeedbackControl
, which contains a proportional controller introduced in the Feedback Control of a ROS-Enabled Robot example. This function subscribes to the /odom
topic to get the current odometry status of the robot, and then publishes the output of a proportional controller as a geometry_msgs/Twist
message to the /cmd_vel
topic. This provides the control commands for the robot to move towards the desired position.
Copy the robotROS2FeedbackControl
function to your local directory and change the defaultDesiredPos
variable to the desired coordinates.
Start a Gazebo Empty World environment for ROS 2 from the Linux virtual machine by running these running commands on the desktop. In the Linux virtual machine for ROS Toolbox, the turtlebot robot is located at the [0,0]
location by default. This Gazebo world contains a Turtlebot robot, which publishes and subscribes to messages on a ROS 2 network.
~$ source /opt/ros/foxy/local_setup.bash ~$ export TURTLEBOT3_MODEL=burger && ros2 launch turtlebot3_gazebo empty_world.launch.py
Create a ros2device
object. Specify the deviceAddress,
username,
and password
values of the Virtual Machine running Gazebo. This establishes an SSH connection between the ROS 2 device and MATLAB.
gazeboVMDevice = ros2device('172.21.17.220',"user","password")
Create a MATLAB ROS 2 node in the same ROS network as the virtual machine. See the list of available ROS 2 nodes.
ros2 node list
Run the controller. The robot is moving towards the published destination. At the same time, observe the trajectory of the robot. Keep this figure open to compare the behavior of MATLAB execution and the generated executable node.
robotROS2FeedbackControl
To change the destination while the robot is moving. Open a new terminal in the virtual machine, source the ROS repository, and publish the new destination coordinates in the form of a std_msgs/Float64MultiArray
message to the /dest
topic.
~$ source /opt/ros/foxy/local_setup.bash ~$ ros2 topic pub -1 /dest std_msgs/Float64MultiArray "{data:[0,0]}"
You can also adjust the distanceThre
, linearVelocity
, and rotationGain
values in the robotROS2FeedbackControl.m
to change the desired robot behavior. For the proportional controller in this example, you must specify values in these ranges to ensure robust performance. Alternatively, you can replace the proportional controller with a custom controller for performance comparison. To view the behavior, reset the robot on the virtual machine by pressing Ctrl-R in Gazebo.
distanceThre: 0<x<1 linearVelocity: 0<x<3 rotationGain: 0<x<6
The controller loop terminates after the robot reaches the goal or if more than 40 seconds has elapsed since the start time. Alternatively, you can terminate the controller at any time using Ctrl-C or entering this command in the terminal from the virtual machine. If you open a new terminal in the virtual machine, you must source the ROS repository.
~$ ros2 topic pub -1 /stop std_msgs/Bool "data: 1"
Create a Function for Code Generation
To generate a standalone C++ node, modify the function to make it compatible for code generation.
Remove the lines of code related to plot.
Save the modified MATLAB function to
robotROS2FeedbackControlCodegen.m
.Ensure any other modifications that you made in
robotROS2FeedbackControl
function are reflected inrobot2ROSFeedbackControlCodegen
.
Generate Executable for robotROS2FeedbackControlCodegen
Reset the Gazebo scene after simulation using Ctrl-R on the virtual machine.
Generate an executable node for the robotROS2FeedbackControlCodegen
function. Specify the hardware as "Robot Operating System 2 (ROS 2)"
. Set the build action to "Build and run"
so that the ROS 2 node starts running after you generate it. Specify the coder configuration parameters for remote deployment. This example specifies the remote device parameters of the virtual machine running Gazebo. Note that the actual values might be different for your remote device. Verify them before deployment.
cfg = coder.config("exe"); cfg.Hardware = coder.hardware("Robot Operating System 2 (ROS 2)"); cfg.Hardware.BuildAction = "Build and run"; cfg.Hardware.RemoteDeviceAddress = '172.21.17.220'; cfg.Hardware.RemoteDeviceUsername = "user"; cfg.Hardware.RemoteDevicePassword = "password"; cfg.Hardware.DeployTo = "Remote Device"; codegen robotROS2FeedbackControlCodegen -args {} -config cfg
Reset the Gazebo scene by using Ctrl-R on the virtual machine and call plotPathFeedbackControl
to plot the robot trajectory.
plotPathFeedbackControl
The configuration generates and runs the ROS 2 node on your remote device. You can opt to deploy and run the ROS 2 node on the local machine by modifying the coder configuration object, cfg
.
cfg = coder.config('exe'); cfg.Hardware = coder.hardware('Robot Operating System 2 (ROS 2)'); cfg.Hardware.BuildAction = 'Build and run'; cfg.Hardware.DeployTo = 'Localhost'; codegen robotROS2FeedbackControlCodegen -args {} -config cfg plotPathFeedbackControl
Verify Generated ROS Node
After the generated executable starts running for the specified destination coordinates, you verify the trajectory of the robot against the MATLAB execution. You can also observe the robot moving in Gazebo on the virtual machine. You can publish a different destination coordinate while the robot is in motion. The Control a ROS-Enabled Robot with a Function section, which shows how to publish a new set of destination coordinates through a virtual machine terminal.
Terminate the generated ROS 2 node by using the stopNode
function of the ros2Device
object. Alternatively, you can terminate the execution by pressing Ctrl-C or sending a message to the /stop
topic. Reset the Gazebo scene by using Ctrl-R on VM Machine.
stopNode(gazeboVMDevice,'robotROS2FeedbackControlCodegen')