-
Notifications
You must be signed in to change notification settings - Fork 5
how to use flightstack
This guide explains how to run and customize the ACSL-flightstack C++ codebase in order to run flight experiments and test existing or new control algorithms.
ACSL-flightstack is a PX4-compatible offboard control framework that runs on an onboard computer, designed for multi-rotor UAVs (uncrewed aerial vehicles) with an array of available control solutions. The control architecture is grouped into an outer loop for translational dynamics and an inner loop for rotational dynamics, which are governed by nonlinear equations of motion.
- UAV platform (e.g., quadcopter or X8-copter)
- Companion computer: Odroid M1S
- Flight controller: Pixhawk 6C
- Motion capture system (VICON) or GPS for state estimation source
- Reliable communication link between companion computer and PX4 (USB/UART)
- Ubuntu 20.04 (running on the companion computer)
- ROS 2 Foxy or ROS 2 Galactic
- PX4 firmware v1.15.0 or above (installed on the flight controller)
- Proper ROS 2 workspace setup and sourcing
- SSH access to the companion computer for deployment and monitoring
The flight stack allows you to select the controller at compile time using preprocessor macros.
File: \include\flightstack\config\config.hpp
/*********************************************************************************************************************
CONTROLLER selection
**********************************************************************************************************************/
// Define named constants for controller types
#define __PID__ 1
#define __MRAC__ 2
#define __TWO_LAYER_MRAC__ 3
#define __FUNNEL_TWO_LAYER_MRAC__ 4
#define __HYBRID_TWO_LAYER_MRAC__ 5
// SELECT here the CONTROLLER you want to run -----------------------------------------------------------------------
#define SELECTED_CONTROLLER __HYBRID_TWO_LAYER_MRAC__
// ------------------------------------------------------------------------------------------------------------------To change the active controller:
- Open
\include\flightstack\config\config.hppin your preferred text editor. - Review the defined constants at the top of the block, which represent the available control algorithms.
- Locate the
#define SELECTED_CONTROLLERdirective. - Replace the assigned macro with the constant corresponding to the controller you wish to run.
For example, to run a standard PID controller instead of the Hybrid Two-Layer MRAC, change the selection line to:
// SELECT here the CONTROLLER you want to run -----------------------------------------------------------------------
#define SELECTED_CONTROLLER __PID__
// ------------------------------------------------------------------------------------------------------------------Important
Because the controller is selected via compile-time macros, you must recompile your codebase after saving your changes to config.hpp for the new controller selection to take effect.
Unlike the controller selection, trajectory and mission parameters are loaded dynamically using a JSON configuration file.
You can configure these settings here:
File: \params\config\config.json
{
...
"user_defined_trajectory_file": "bean_trajectory0p3.json",
"hover_after_trajectory_time_seconds": 5.0,
...
}Key Trajectory Parameters
-
user_defined_trajectory_file: Defines the specific trajectory the UAV will execute during the flight. All available trajectory files that you can choose from are located in the\params\user_defined_trajectory\directory. -
hover_after_trajectory_time_seconds: Specifies the amount of time (in seconds) the UAV will hover in place after successfully completing the trajectory, right before it initiates the landing sequence.
Note
Because these parameters are read at run-time, any changes you make to this config.json file take effect immediately. You do not need to recompile the codebase when swapping trajectories or adjusting hover times.
Just like the trajectory parameters, the control gains for your selected algorithm are loaded dynamically at run-time. If you selected the standard PID controller, its gains are defined in a dedicated JSON file.
You can view and adjust these tuning parameters according to the following.
File: \params\control\pid\gains_pid.json
{
"KP_translational": {
"scaling_coef": 1.0,
"matrix": [
[14.0, 0.0, 0.0],
[0.0, 14.0, 0.0],
[0.0, 0.0, 25.0]
]
},
...
"KP_rotational": {
"scaling_coef": 1.0,
"matrix": [
[18.0, 0.0, 0.0],
[0.0, 18.0, 0.0],
[0.0, 0.0, 10.0]
]
},
...
}Understanding the Gain Matrices The control architecture separates the tuning into two distinct loops:
-
Translational Gains (
_translational): Tunes the outer loop, which dictates the UAV's translational position and velocity. -
Rotational Gains (
_rotational): Tunes the inner loop, which dictates the UAV's attitude (orientation) and angular rates.
For each control gain, you will configure two elements:
-
matrix: A matrix where the diagonal values usually represent the individual gains for the X, Y, and Z axes of the inertial refernece frame. -
scaling_coef: A global multiplier applied to the entire matrix. This is highly useful for field tuning; if you want to increase or decrease the overall aggressiveness of a specific gain without recalculating the individual matrix entries, you can simply adjust this coefficient (e.g., setting it to1.2increases all values in that matrix by 20%).
Note
Because these files are read at run-time, you can tweak your gains between flight tests and see the results immediately on your next run. No recompilation is required.
To compute the desired attitude rates and accelerations smoothly, the flight stack uses a state-space representation of a continuous-time linear differentiator. You can configure the state-space matrices (
You can view and adjust these parameters according to the following.
File: \params\control\differentiator_gains.json
{
"A_filter_roll_des": {
"scaling_coef": 1.0,
"matrix": [
[-72, -1600],
[1, 0]
]
},
...
"C_filter_roll_dot_des": {
"scaling_coef": 0.15,
"matrix": [
[2500, 0]
]
},
"D_filter_roll_dot_des": 0.0
}Differentiator formulation
The differentiator acts as a second-order filter defined by a cut-off frequency (
Configuring the matrices
The JSON file separates the tuning into two levels of differentiation for both roll (
-
First Derivative (
_roll_des,_pitch_des): Computes the desired angular rates (roll rate and pitch rate). -
Second Derivative (
_roll_dot_des,_pitch_dot_des): Computes the desired angular accelerations (roll acceleration and pitch acceleration).
For each matrix, you configure:
-
matrix: The raw values representing the state-space system derived from your chosen$\omega_0$ and$\xi$ . -
scaling_coef: A global multiplier for that specific matrix.
Note
Because these parameters are read at run-time, any changes you make to the differentiator gains take effect immediately on your next flight test. No recompilation is required.
The physical properties and geometric configuration of your UAV are defined in a C++ header file. This includes the mass, inertia matrix, motor thrust limits, aerodynamic drag, and the mixer matrices used to map control efforts to individual motors.
You can view and modify these characteristics according to the following.
File: \include\flightstack\control\vehicle_info.hpp
...
inline constexpr double UPPER_MOTOR_THRUST_SATURATION_LIMIT_IN_NEWTON = 9.5;
inline constexpr double LOWER_MOTOR_THRUST_SATURATION_LIMIT_IN_NEWTON = 0.3;
inline constexpr double MINIMUM_VALUE_PUBLISH_MOTORS = 0.05;
struct VehicleInfo
{
const double mass = 1.920; // [kg] vehicle mass
const Eigen::Matrix3d inertia_matrix = (Eigen::Matrix3d() <<
2.271990e-02, -6.557000e-06, -1.003498e-03,
-6.557000e-06, 2.202047e-02, 5.658400e-06,
-1.003498e-03, 5.658400e-06, 1.614693e-02
).finished(); // [kg*m^2] inertia matrix of the vehicle system
...
const double distance_motors_cenetrline_x_dir = 0.0881269; // [m] distance along x direction
const double distance_motors_cenetrline_y_dir = 0.1083450; // [m] distance along y direction
const double propeller_drag_coefficient = 0.01; // [m]
...
};Key vehicle parameters
-
Motor limits: Constants like
UPPER_MOTOR_THRUST_SATURATION_LIMIT_IN_NEWTONdefine the physical clipping limits for your propulsion system. -
Rigid body properties: The
massandinertia_matrixmust accurately reflect your fully assembled UAV for the model-based controllers to function correctly. -
Geometry & mixing: The
distance_motors_cenetrlinevariables define your drone's physical dimensions. These are used directly to populate themixer_matrix(for X8-copter setup) andmixer_matrix_quadcopter(for quadcopter setup), which map the overall desired translational and rotational forces and moments to specific motor outputs. -
Thrust curve (
thrust_polynomial_coefficients_quadcopter): A vector of coefficients representing the empirical polynomial curve that converts commanded thrust (in Newtons) into normalized 0 to 1 signals.
Important
Because these vehicle characteristics are hardcoded into a C++ struct, you must recompile your codebase after saving any changes to vehicle_info.hpp for them to take effect.
ACSL-flightstack — PX4-compatible offboard flight stack designed for multi-rotor UAVs Developed by Mattia Gramuglia, Giri Mugundan Kumar and Andrea L'Afflitto
- How to Set Up Hardware and Software
- How to Use the Flightstack
- Structure of the UAV Control System
- Fundamentals of adaptive control