Main Content

Plant and Attitude Controller Model for Hexacopter

The UAV Toolbox Support Package for PX4® Autopilots contains a plant and an attitude controller model to fly a hexacopter drone that uses a Pixhawk® Series flight controller.

Simulate the Plant Model for Hexacopter

The plant model, px4demo_attitude_plant, simulates the 6 DOF, and it outputs the roll, pitch, yaw and thrust values, which are then fed to the InputConditioning subsystem in the px4demo_attitude_control model. The attitude controller generates PWM pulse widths which are then provided to the plant as feedback.

To open the plant model, enter the following command at the MATLAB® prompt:

px4demo_attitude_plant

This plant model simulates the behavior when the roll command from the RC Transmitter varies; the pitch, yaw and thrust values are kept constant. The model can be modified to simulate changes for pitch and yaw as well.

The px4demo_attitude_control subsystem takes the roll, pitch, yaw and thrust values as input from user. It also accepts the vehicle attitude and IMU measurements for gyroscope. These values are then fed to the PID controller. The output of PID controller is fed to the mixer matrix for hexacopter to output the PWM pulse widths. The PID controller might need to be tuned according to your airframe. The mixer matrix will vary from airframe to airframe.

Generate Code for Controller for Hexacopter

The controller model, px4demo_attitudeSystem, gathers the inputs from Gyroscope, Radio Controller and Vehicle Attitude block and sends them to the attitude controller px4demo_attitude_control, which returns the PWM pulse widths which are then published.

To open the controller model, enter the following command at the MATLAB prompt:

px4demo_attitudeSystem

Build the above model and deploy it to the selected Pixhawk Series flight controller.

Adapting the Plant and Attitude Controller for Other Airframes

For modifying the controller for any other airframes, the corresponding mixer matrix needs to be added by replacing the existing motor_mixer function block in px4demo_attitude_control model.

The PID controller also needs to be tuned according to the airframe.