Keyboard shortcuts

Press or to navigate between chapters

Press S or / to search in the book

Press ? to show this help

Press Esc to hide this help

PX4 Integration

Pictorus now offers the ability to integrate a Pictorus model as a PX4 module that can run on the PX4 platform - both in the Gazebo simulator and on physical hardware.

Getting Started

A fully working Pictorus PX4 integration will require a PX4 development environment, which typically involves setting up a Linux environment with the necessary tools and dependencies for building PX4 firmware. You can follow the official PX4 setup guide to set up a local environment.

The following examples were built using a Debian based Linux. The examples also uses a PlayStation controller to provide manual control inputs to the PX4 simulation and physical hardware.

Create a PX4 Model in Pictorus

Pictorus PX4 modules use Rust bindings to subscribe to and publish uORB messages. uOrb is PX4's native communication protocol for inter-module communication. It is a pub-sub system, where "topics" are used to advertise and receive specific message types . We are building a simple model that subscribes to the Sensor Gyro and Manual Control Setpoint uORB topics. These subscriptions bring data into the model, where it is modified and converted to PWM timing values. Finally, those values are published to the Actuator Motors uORB topic, this exports data from the model, back into the the broader PX4 system.

  1. Create a new model in Pictorus.
  2. Open the App Settings from the left sidebar and change the Platform to PX4_Linux. This will change the default Input and Output block set to PX4 compatible blocks.
  3. Drag and drop a uORB Input block from the left sidebar into the model. Double click on the block to open the block parameters and select Sensor Gyro from the Message dropdown. This will configure the block to subscribe to the Sensor Gyro uORB topic.
  4. Drag and drop another uORB Input block into the model. Double click on the block and select Manual Control Setpoint from the Message dropdown. This will configure the block to subscribe to the Manual Control Setpoint uORB topic.
  5. Drag and drop a uORB Output block into the model. Double click on the block and select Actuator Motors from the Message dropdown. This will configure the block to publish to the Actuator Motors uORB topic.
  6. Build out the rest of the model to process the input data and generate PWM duty cycles. Below is an example of basic model that can be used as a starting point. PX4 documentation discusses existing models and control strategies that can also be used in Pictorus. PX4 Model Example PX4 Component

Note:

  • The Actuator Motors uORB topic expects a 12x1 array of floating point motor PWM values. We use a Vector Merge block to merge the 4 motor commands with 8 zeros to create a 1x12 array and transpose it to a 12x1 array using a Matrix Transpose block.
  • The order of the motors should match the order expected by PX4. You can run QGroundControl before proceeding to the next section which will show the motor order. This is why component outputs 2 and 3 are swapped going into the Vector Merge block. This image shows the motor order for the x500 simulation drone. PX4 Motor Order

Testing a Pictorus Model using Simulation in the Loop (SITL)

Once you have created your PX4 model in Pictorus, you can export it as a static library that can be linked into the PX4 framework. Pictorus compiles the model to Rust and provides C Foreign Function Interface (FFI) bindings and PX4 model shim code to make it easy to link the generated library into PX4 as a module.

Additional Requirements

  • QGroundControl: Provides additional tools for interacting with the simulated drone, such as mapping control inputs from a controller to the simulation environment.
  • PlayStation Controller: This example uses a PlayStation controller for manual control inputs. Other controllers may work, but additional configuration may be needed.

Configure QGroundControl to use the PlayStation Controller

  1. If you have a controller connected, go to Vehicle Configuration -> Joystick -> Active Joystick and select your controller from the dropdown menu.

Export the PX4 Model for testing in the Gazebo simulation environment

  1. From the Pictorus web UI, open Export App from the left sidebar.
  2. Select PX4_Linux platform.
  3. Select PX4_LinuxX86 as the target if the Linux computer running PX4 and Gazebo is x86 based. Select PX4_LinuxARM if the Linux computer is ARM based.
  4. Select Static Lib as the output type.
  5. Click Build and wait for the build to complete.
  6. Once the build is complete, click Download Source to download the generated source code in a zip file. The PX4 zip file contains:
  • lib.rs: The Rust model code
  • lib<model_name>_<app_id>.a: The compiled static library
  • module_shim folder: Contains the C FFI bindings and PX4 wrapper code to link the static library into PX4.
  1. Create a new folder in your PX4-Autopilot repository, for this example we will create PX4-Autopilot/pictorus_x86 and extract the contents of the zip file into this folder.
  2. Open a terminal in the PX4-Autopilot folder and run: make px4_sitl gz_x500 EXTERNAL_MODULES_LOCATION=./pictorus_x86/module_shim. This will build PX4 with the Pictorus module included and launch Gazebo populated with an x500 drone model. This terminal will also act as the PX4 console for the simulation for subsequent steps in this section.

Note: The EXTERNAL_MODULES_LOCATION does not need to be at ./pictorus_x86/module_shim, it just needs to point to the module_shim folder.

  1. Stop the built in PX4 multi-copter controllers by running the following commands in the PX4 console:
  • mc_rate_control stop: Disables the multi-copter rate controller
  • mc_att_control stop: Disables the multi-copter attitude controller
  • mc_pos_control stop: Disables the multi-copter position controller

These modules are also trying to publish to the Actuator Motors uORB topic and will conflict with the Pictorus module.

  1. Arm the drone by running commander arm.

Optional: To prevent from having to disable the mc_*_control modules every time, you can modify the Simulation startup script located at PX4-Autopilot/build/px4_sitl_default/rootfs/etc/init.d-posix/rcS and add the following lines at the end of the file:

mc_rate_control stop
mc_att_control stop
mc_pos_control stop
commander arm

This should disable the multi-copter controllers and arm the drone automatically when the simulation starts.

  1. Start the Pictorus module by running pictorus_module start which runs the Pictorus module, launching the model and publishing motor commands to the Actuator Motors uORB topic.
  2. Gently provide some throttle using the PlayStation controller to see the motors spin up and observe the motors when changing the roll, pitch, and yaw inputs.
  3. To stop the Pictorus module, run pictorus_module stop. PX4 Gazebo Simulation

Deploy the Model to PX4 Hardware

Once you have tested your PX4 model in the Gazebo simulator, you can bundle the Pictorus model into deployable PX4 firmware to run on physical hardware.

Additional Requirements

  • Physical Hardware: This example uses a Holybro Pixhawk 6X-RT flight controller.
  • QGroundControl: Can be used for uploading firmware to the flight controller and interacting with the PX4 shell on the hardware.
  • mavlink_shell.py script: This script can be used to connect to the PX4 shell over MAVLink and is an alternative to using the QGroundControl console.
  • Logic Analyzer (Optional): A logic analyzer can be helpful for debugging PWM outputs to motors.

Deploy the Model to PX4 Hardware

  1. Open the model from the previous section in Pictorus.
  2. Open Export App from the left sidebar.
  3. Select PX4_STM32 platform.
  4. Select the appropriate target for your hardware. For the Pixhawk 6X-RT, select PX4_STM32H7.

Note: We are reworking this to be more intuitive. The 6X-RT uses a Cortex-M7 processor, which is why we select the PX4_STM32H7 target. The PX4 library does not interact with any chip specific peripherals, the processor name is a stand-in for the chip architecture and instruction set when compiling the static library.

  1. Select Static Lib as the output type.
  2. Compile the model by clicking Build and wait for the build to complete.
  3. Once the build is complete, click Download Source to download the generated source code as a zip file. The folder structure is the same as the previous section.
  4. Create a new folder in your PX4-Autopilot repository, for this example we will create PX4-Autopilot/pictorus_arm and extract the contents of the zip file into this folder.

QGroundControl Firmware Upload

QGroundControl can be used to upload the generated firmware to the flight controller and interact with the PX4 shell on the hardware.

  1. Open a terminal in the PX4-Autopilot folder and run: make px4_fmu-v6x EXTERNAL_MODULES_LOCATION=./pictorus_arm/module_shim. This will build the PX4 firmware with the Pictorus module included and generate a px4_fmu-v6xrt_default.px4 firmware file in the PX4-Autopilot/build/px4_fmu-v6x_default folder.
  2. Open QGroundControl and navigate to the Firmware tab under Vehicle Configuration.
  3. Unplug and re-plug in the flight controller to enter the bootloader mode.
  4. Check the Advanced Settings box and select Custom Firmware File from a now visible drop down menu and navigate to the px4_fmu-v6xrt_default.px4 firmware file generated above. Click Update Firmware to upload the firmware to the flight controller. QGroundControl Firmware
  5. After the firmware is uploaded and the flight controller reboots, go to Analyze Tools and select the Mavlink Console tab.

Console Firmware Upload

Alternatively, you can use the make file upload command and mavlink_shell.py script to upload and interact with the flight controller. The PlayStation controller probably won't work with this method without additional configuration settings and input mapping not covered in this document.

  1. Ensure the flight controller is connected and open a terminal in the PX4-Autopilot folder and run: make px4_fmu-v6x EXTERNAL_MODULES_LOCATION=./pictorus_arm/module_shim upload. This will build the PX4 firmware and attempt to upload it to the connected flight controller.
  2. Once the upload is complete, you can use the mavlink_shell.py by running ./Tools/mavlink_shell/mavlink_shell.py <flight_controller_serial_port>, replacing <flight_controller_serial_port> with the serial port of your flight controller (i.e. /dev/ttyACM0) from the PX4-Autopilot folder. This will open a PX4 shell connected to the flight controller over MAVLink.

Starting the Pictorus Module on PX4 Hardware

Once the firmware with the Pictorus module is uploaded to the flight controller, you can start the module from the PX4 shell.

WARNING: Running a new flight model on physical hardware can be dangerous and unpredictable while the model is under development and being tuned. Ensure the vehicle is restrained and cannot take off or cause harm to people or property. Always have a way to cut power to the motors in case of unexpected behavior.

  1. Stop the built in PX4 multi-copter controllers by running the following commands in the PX4 console:
  • mc_rate_control stop: Disables the multi-copter rate controller
  • mc_att_control stop: Disables the multi-copter attitude controller
  • mc_pos_control stop: Disables the multi-copter position controller

Optional: To prevent from having to disable the mc_*_control modules every time, you can add a file to the flight controller's SD card called /etc/rc.txt and add:

mc_rate_control stop
mc_att_control stop
mc_pos_control stop
commander mode manual

This script will run commands in the rc.txt file at boot and put the vehicle in manual mode, which makes it easier to visualize the motor outputs through subsequent firmware updates. commander mode manual puts the vehicle in manual mode, which is useful for testing motor outputs, but may not be safe for flight or the surrounding environment.

Optional: Hook up a logic analyzer to the PWM pins that have been configured as motor outputs to visualize the PWM signals being sent to the motors before testing with motors connected.

  1. Arm the drone by running commander arm, you may need to pull back on the controller throttle as directed by QGroundControl.
  2. Start the Pictorus module by running pictorus_module start. This will start the Pictorus module, running the model and publishing motor commands to the Actuator Motors uORB topic. PX4 Console
  3. Gently provide some throttle to see the motors spin up and observe the motors when changing the roll, pitch, and yaw inputs. The movie below shows the logic analyzer software acquiring the PWM signals from the Pixhawk 6X-RT running the Pictorus module. PX4 Hardware Test
  4. To stop the Pictorus module, run pictorus_module stop.