E-42/reports/2022-12-16_px4_simulation_monkin.md

135 lines
9.0 KiB
Markdown
Raw Normal View History

2022-12-16 12:56:32 +00:00
## SITUATION REPORT 4 (16/12/2022)
# How to setup a PX4 simulation using SITL
## Introduction
This report aims to describe the steps to setup a simulation environment for the *Pixhawk* board. The simulation will be done using the *PX4* software, which is the most common software used in the *Pixhawk* board.
Simulators allow PX4 flight code to control a computer modeled vehicle in a simulated world. It is possible to interact with this vechicle just as you might with a real vehicle, using *QGroundControl*, an offboard API, or a radio controller.
PX4 supports both SITL (Software in the loop) and HITL (Hardware in the loop) simulations. This guide is targeted for SITL simulation, where the flight code runs on the same computer as the simulator.
---
## Supported Simulators
While PX4 supports other simulators, the following are the most relevant for our use case:
| Simulator | Description | Supported Vehicles |
|---|---|---|
| jMAVSim | A simple multirotor simulator that allows you to fly copter-type vehicles around a simulated world. It is easy to set up and can be used to test if the vehicle can take-off, fly, land, and responds approprietly to various fail conditions (e.g GPS failure). Multi-vehicle simulation is also supported. | Quad |
| Gazebo | A powerful 3D simulation environment that is particularly suitable for testing object-avoidance and computer vision. It can also be used for multi-vehicle simulation and is commonly used with ROS, a collection of tools for automating vehicle control. | Quad (Iris and Solo, Hex (Typhoon H480), Generic quad delta VTOL, Tailsitter, Plane, Rover, Submarine |
| FlightGear | A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. Multi-vehicle simulation is also supported. | Plane, Autogyro, Rover |
**PX4** contains documentation regarding the set up of each simulator. The following sections will focus on the *jMAVSim* simulator, as it is the simplest to set up and, as of right now, seems to contain all the features required for our use case.
### Simulator MAVLink API
All simulators communicate with PX4 using the *Simulator MAVLink API*. This API defines a set of messages that **supply sensor data** from the simulated world to PX4 and return motor and actuator values from the flight code that will be applied to the simulated vehicle. The image below depicts the flow of information between the simulator and PX4:
2022-12-16 12:56:32 +00:00
![MavLink Message Flow](assets/Pixhawk/px4_mavlink_msg_flow.png)
Note: A SITL build of PX4 uses [SimulatorMavlink.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp) to handle these messages. To see the messages that are exchanged in more detail, visit the [documentation page](https://docs.px4.io/main/en/simulation/#simulator-mavlink-api).
#### Default PX4 MAVLink UDP Ports
By default, PX4 uses commonly established ports for MAVLink communication with Ground Control Stations (e.g QGroundControl), offboard APIs (e.G MAVSDK) and simulator APIs (e.g jMAVSim). The following table shows the default ports used by PX4:
| Port | Description |
|---|---|
| UDP 14550 | Communication with Ground Control Stations, such as QGroundControl. |
| UDP 14540 | Communication with offboard APIs. |
| TCP 4560 | Communication with PX4 (flight code). The simulator listens to this port and PX4 initiates a connection to it. |
## SITL Simulation Environment
The diagram below shows a typical SITL simulation environment:
2022-12-16 12:56:32 +00:00
![PX4 Simulation Environment](assets/Pixhawk/px4_sitl_environment.png)
The different parts of the system connect via UDP, and can be run on either the same computer or another computer on the same network.
PX4 uses a simulation-specific module to connect to the simulator's local TCP port 4560. Simulators then exchange data with PX4 using the MAVLink API described above. PX4 on SITL and the simulator can run on either the same machine or on different machines on the same network.
2022-12-18 13:32:31 +00:00
---
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
## Simulation Coding Environment
Unfortunately, the PX4 documentation is not very clear regarding the necessary coding environment. However, from the information provided and my own research, I concluded that the simulation software works in the following conditions:
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
1. Windows + Windows Subsystem for Linux 2 (WSL2 with Ubuntu-20.04 distro)
2. Ubuntu 18.04
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
The software does not have a great set up experience, as it requires some manual configuration. In other Ubuntu versions, I wasn't capable to run the simulation. Therefore, in order to have my work environment without virtual machines or even installing a new OS just for this task, I proceeded with the first option.
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
### Windows + WSL2 (Ubuntu-20.04)
Before starting the installation, I want to highlight that the **Ubuntu distro used was 20.04**. I cannot guarantee that the installation will work in other versions as the setup from my experience is dependent on the Ubuntu version.
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
The installation steps can be followed [here](https://docs.px4.io/main/en/dev_setup/dev_env_windows_wsl.html). Even after following the steps listed in the documentation, the installation was not successful. An error related with the `protobuf` library inside WSL occurred. Luckily, simply uninstalling and installing again the library solved the problem:
```bash
# Uninstall the previous version
sudo apt remove protobuf-compiler
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
# Installing protobuf again
sudo apt install protobuf-compiler
```
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
I was able to replicate the setup in a second computer and, at the second time, this *protobuf* error didn't occur.
2022-12-16 12:56:32 +00:00
2022-12-19 19:25:00 +00:00
To sum up the installation steps present in the [guide](https://docs.px4.io/main/en/dev_setup/dev_env_windows_wsl.html):
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
1. Install WSL2 according to the docs in the specific version (Ubuntu-20.04)
2. Install the PX4 toolchain
```bash
# Clone PX4 Repo
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
# Run Setup script (Installs PX4, JMavSim and Gazebo)
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
```
3. Run the simulation (jMAVSim + PX4 bundled together)
```bash
HEADLESS=1 make px4_sitl_default jmavsim
```
2022-12-16 12:56:32 +00:00
2022-12-19 19:25:00 +00:00
The `HEADLESS` flag avoids running the jMAVSim GUI, as it does not seem to work with the WSL2. However, I did not consider this to be a problem, as *QGroundControl* will be used during development as a ground station.
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
4. Install *QGroundControl* to visualize the simulation and control the vehicle. You can follow [these instructions](https://docs.px4.io/main/en/dev_setup/dev_env_windows_wsl.html#qgroundcontrol) to install it. It can be installed on Windows or directly on WSL2. Personally, I installed it on Windows as it allows to flash the firmware to the Pixhawk board later on. However, to work on windows, it's necessary to create a **communication link** in the QGroundControl Settings, as explained in the guide.
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
---
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
## jMAVSim Simulator
2022-12-19 19:25:00 +00:00
jMAVSim is a simple multirotor/Quad simulator that allows you to fly *copter* type vehicles running *PX4* around a simulated world.
2022-12-16 12:56:32 +00:00
2022-12-19 19:25:00 +00:00
After running the simulation, through `HEADLESS=1 make px4_sitl_default jmavsim`, you should see the terminal output similar to the one below, mentioning that the vehicle is ready for takeoff.
2022-12-19 19:25:00 +00:00
![SITL terminal upon start](assets/Pixhawk/px4_sitl_terminal_start.png)
2022-12-16 12:56:32 +00:00
2022-12-19 19:25:00 +00:00
Additionally, if you setup the QGroundControl comm link correctly, you should see the vehicle in the simulation environment with the indicator on the top right corner, indicating that the vehicle is ready to be controlled.
2022-12-19 19:25:00 +00:00
![QGroundControl connected](assets/Pixhawk/qgroundcontrol_ready.png)
There you have it. That wraps up the setup of the simulation environment. Now, it is possible to start developing the software for the rocket. To test the PX4 firmware is working, type `help` in the terminal to see the available commands and execute one of them, for example `commander takeoff` to make the vehicle takeoff.
2022-12-16 12:56:32 +00:00
2022-12-18 13:32:31 +00:00
---
2022-12-16 12:56:32 +00:00
## Conclusion and Next Steps
2022-12-19 19:25:00 +00:00
This report covered the necessary information to start developing the software for the rocket in a simulation environment. As shown, the initial configuration is far from ideal, but this document should help to avoid most of the problems during the setup.
As of right now, I only created a simple `hello world` command to test the software. The next steps involve experimenting the PX4 software in more complex scenarios, more fitting to a rocket use case. Furthermore, the vehicle setup requires some fine tuning to enable some sensors, such as the *radio transceiver*.
2022-12-19 19:25:00 +00:00
![QGroundControl summary](assets/Pixhawk/qgroundcontrol_summary.png)
Finally, there's more work to be done in other areas, namely: Choosing the Pixhawk board, the sensors and investigating how to relate the [SAVOIR architecture](https://savoir.estec.esa.int/) with the current software.
2022-12-16 12:56:32 +00:00
## References
\[1\] [PX4 Docs](https://docs.px4.io/main/en)
2022-12-19 19:25:00 +00:00
\[2\] [QGroundControl](http://qgroundcontrol.com/)
\[3\] [SAVOIR](https://savoir.estec.esa.int/)
2022-12-16 12:56:32 +00:00
2022-12-19 19:25:00 +00:00
\[4\] [Microsft WSL Installation](https://learn.microsoft.com/en-us/windows/wsl/install)
2022-12-16 12:56:32 +00:00
<br>
<div style="text-align: right">Published by João Mesquita</div>