Monitor and Tune PX4 Host Target Flight Controller with Simulink-Based Plant Model
This example shows how to use the UAV Toolbox Support Package for PX4 Autopilots to verify the controller design using PX4 Host Target versus the simulator designed in Simulink®.
The UAV Toolbox Support Package for PX4 Autopilots enables you to use Simulink to design a flight controller algorithm to stabilize the vehicle based on the current vehicle attitude, position, and velocity and also track the desired attitude using Simulink. The MAVlink blocks in the UAV Toolbox enable you to read and write the MAVLink HIL_* messages and design the plant dynamics.
This example shows how to validate a position controller design on a medium-sized quadrotor plant using a single Simulink model, and then take the same controller and plant model and simulate it with the PX4 source code in, what the PX4 community calls it, Software In The Loop (SITL) simulation.
Prerequisites
If you are new to Simulink, watch the Simulink Quick Start video.
Perform the initial Setup and Configuration of the support package using Hardware Setup screens. In the Select a PX4 Autopilot and Build Target screen, select
PX4 Host Target
as the PX4 Autopilot board from the drop-down list.
For more information on how to verify the controller design using the jMAVSim simulator, see Deployment and Verification Using PX4 Host Target and jMAVSim and Position Tracking for X-Configuration Quadcopter Using Rate Controller.
For more information on designing the controller model and verifying it using the simulator plant model designed in Simulink, see Integrate Simulator Plant Model Containing MAVLink Blocks with Flight Controller Running on PX4 Host Target.
Model
To get started, launch the Simulink Px4DemoHostTargetWithSimulinkPlant project.
Once the project launches, it will load the required workspace variables and open the top model.
Model Architecture and Conventions
This project consists of the following models:
The
Quadcopter_controller
is the harness model that contains the flight controller. The model is set up to run with the PX4 source code by creating a PX4 Host Target executable.
The
Quad_UAV_dynamics
harness model contains the UAV plant dynamics. This harness model is set up to run in normal simulation pacing mode in lockstep with theQuadcopter_controller
harness model.
The Project shortcuts guide you through the tasks as you progress through the example.
Task: Deploy Controller as Host Target and Run Plant Model in Simulink
In this task, we use the controller and run it with PX4 source code using the PX4 Host Target feature (for more information, see Integrate Simulator Plant Model Containing MAVLink Blocks with Flight Controller Running on PX4 Host Target). Use two separate instances of MATLAB to run controller and plant model.
Step 1: Launch Controller Model
1. Click the Step 1: Deploy Quad controller on Host Target in the Project Shortcuts tab to open the Quadcopter_controller
model.
The uORB Read blocks are used to subscribe to the vehicle_local_position
and vehicle_attitude
topics. These topics contain data sent by the simulator plant model using HIL_STATE_QUATERNION and HIL_GPS messages.
The Controller subsystem designs the Rate controller and the Position and Attitude controller as explained in Position Tracking for X-Configuration Quadcopter Using Rate Controller.
The FlightController
model outputs the actuator values that are then fed to the PX4 PWM Output block.
2. Copy the MATLAB Project Path to clipboard.
Step 2: Launch Simulink Plant model in second MATLAB
1. Open the second instance of the same MATLAB version.
2. Navigate to the project path previously copied in current MATLAB.
3. Click on the .prj
file to launch the same Project in current MATLAB.
4. Click Step 2: Run Quad dynamics simulation in the Project Shortcuts tab to open the Quad_UAV_dynamics
model.
Ensure that the Simulation Pacing option for this model is enabled, as described in Integrate Simulator Plant Model Containing MAVLink Blocks with Flight Controller Running on PX4 Host Target.
The TCP read from PX4 Host Target
MATLAB System block is used to read the MAVLink data sent from the px4Demo_FlightController_top
model.
The Enabled subsystem has the MAVLink Deserializer block that extracts the HIL_ACTUATOR_CONTROLS message.
The TCP write to PX4 Host Target
MATLAB System block sends the HIL_SENSOR, HIL_GPS, and HIL_STATE_QUATERNION MAVLink messages to the px4Demo_FlightController_top
model.
Step 3: Deploy controller model over Monitor & Tune and run Plant Simulation
1. In Configuration parameters > Hardware Implementation, set the Hardware board parameter to PX4 Host Target
.
2. Under Target hardware resources > Build Options, set Simulator to Simulink
.
3. In the Simulation tab, set the Simulation Stop time to inf.
4. On the Hardware tab, in the Mode section, select Run on board and then click Monitor & Tune to start signal monitoring and parameter tuning.
5. Wait for Simulink to complete the code generation. The following dialog box appears. Do not click OK yet.
In the plant model launched in second MATLAB, follow the below steps.
1. In the Simulation tab, set the Simulation Stop Time to inf.
2. Click Run on the Simulation Tab.
After the simulation starts in the plant model, click OK in the dialog box of the first model.