ROS/MAVROS with Gazebo Classic Simulation
Last updated
Last updated
ROS (Robot Operating System) can be used with PX4 and the Gazebo Classic simulator. It uses the MAVROS MAVLink node to communicate with PX4.
The ROS/Gazebo Classic integration with PX4 follows the pattern in the diagram below (this shows the generic PX4 simulation environment). PX4 communicates with the simulator (e.g. Gazebo Classic) to receive sensor data from the simulated world and send motor and actuator values. It communicates with the GCS and an Offboard API (e.g. ROS) to send telemetry from the simulated environment and receive commands.
:::note The only slight difference to "normal behaviour" is that ROS initiates the connection on port 14557, while it is more typical for an offboard API to listen for connections on UDP port 14540. :::
:::note ROS is only supported on Linux (not macOS or Windows). :::
The easiest way to setup PX4 simulation with ROS on Ubuntu Linux is to use the standard installation script that can be found at Development Environment on Linux > Gazebo with ROS. The script installs everything you need: PX4, ROS "Melodic", the Gazebo Classic 9 simulator, and MAVROS.
:::note The script follows the standard ROS "Melodic" installation instructions, which includes Gazebo 9. :::
The command below can be used to launch the simulation and connect ROS to it via MAVROS, where fcu_url
is the IP / port of the computer running the simulation:
To connect to localhost, use this URL:
:::note It can be useful to call roslaunch with the -w NUM_WORKERS
(override number of worker threads) and/or -v
(verbose) in order to get warnings about missing dependencies in your setup. For example:
:::
The Gazebo Classic simulation can be modified to integrate sensors publishing directly to ROS topics e.g. the Gazebo Classic ROS laser plugin. To support this feature, Gazebo Classic must be launched with the appropriate ROS wrappers.
There are ROS launch scripts available to run the simulation wrapped in ROS:
posix_sitl.launch: plain SITL launch
mavros_posix_sitl.launch: SITL and MAVROS
To run SITL wrapped in ROS the ROS environment needs to be updated, then launch as usual:
(optional): only source the catkin workspace if you compiled MAVROS or other ROS packages from source:
Include one of the above mentioned launch files in your own launch file to run your ROS application in the simulation.
This section shows how the roslaunch instructions provided previously actually work (you can follow them to manually launch the simulation and ROS).
You will need three terminals, in all of them the ros environment must be sourced.
First start the simulator using the command below:
The console will look like this:
In the second terminal make sure you will be able to start gazebo with the world files defined in PX4-Autopilot. To do this set your environment variables to include the appropriate sitl_gazebo-classic
folders.
Now start Gazebo Classic like you would when working with ROS
In the third terminal make sure you will be able to spawn the model with the sdf files defined in PX4-Autopilot. To do this set your environment variables to include the appropriate sitl_gazebo-classic
folders.
Now insert the Iris quadcopter model like you would when working with ROS. Once the Iris is loaded it will automatically connect to the px4 app.