Offboard Control Overview

Offboard control architecture overview using Clover platform

An explanaton of offboard control is discussed on the Clover website:

The simple_offboard module of the clover package is intended for simplified programming of the autonomous drone flight (OFFBOARD flight mode). It allows setting the desired flight tasks, and automatically transforms coordinates between frames.

simple_offboard is a high level system for interacting with the flight controller. For a more low level system, see mavros.

Main services are get_telemetry (receive telemetry data), navigate (fly to a given point along a straight line), navigate_global (fly to a point specified as latitude and longitude along a straight line), land (switch to landing mode).

The following section gives brief descriptions on how the low level controllers handle the high level commands sent from these functions within simple_offboard and details how they use mavros to accomplish the setpoint publishing. Also, a modified simple_offboard module is discussed in section Feedforward Simple Offboard where feedforward control is implemented through the navigate function.

Control Architecture

An overview of the PX4 control architecture will be presented to give the user a better understanding one how to publish setpoints, how they are handled and what kind of control is needed. A simplified overview of the control structure within PX4 can be seen:

The position control module is in the inertial reference frame and the attitude control module is in the body reference frame. The innermost controllers are the angular rate controllers and the outer most ones are the position controllers where PID stands for Proportional, Integral, and Derivative controllers. It is assumed the user has a basic understanding of PID controller. A table highlighting each parameter from the figure is presented:

Control SignalDescription

X_sp

Inertial position setpoint

psi_sp

Yaw setpoint

V_sp

Inertial linear velocity setpoint

A_sp

Inertial linear acceleration setpoint

q_sp

Unit quaternion setpoint

Omega_sp

Body angular rate setpoint

detla_{A_sp}

Aileron setpoint

detla_{E_sp}

Elevator setpoint

detla_{R_sp}

Rudder setpoint

detla_{T_sp}

Total thrust setpoint

T_sp

Actuator input setpoint

For the interest of the reader, a brief overview of the control structure and important control parameters within PX4 are explained in the following video:

Using Offboard control mode allows the user to autonomously control the Clover without using the RC transmitter. This means we can send setpoints to the control signals as desired. A quadcopter is inherently unstable therefore each control level offers an additional layer of stability allowing for easier implementation for the user. We will discuss various publishing methods used for autonomous control.

The current simpleoffboard module provided by Clover has three main publishing functions. A description of this module can be found on the COEX website. The publishing method and how PX4 control architecture handles these messages will be described in the following sections. The five main functions of interest are listed:

Publishing to position control module

This is the method used throughput the rest of the documentation, and how Clover sets up the simpleoffboard module to control the Clover. It is similar to operating in Position Mode with the RC transmitter where velocity setpoints are used. High-level control commands are sent to the PX4 such as position, velocity , or acceleration set-points. The PX4 will receive those set-points in the position control module to perform the necessary control actions before sending setpoints to the low-level controllers (e.g. attitude/engines control). Clover has developed a module that uses MAVROS to provide users a friendly and compact way in sending offboard commands to the Clover detailed here. Before explaining further, we can take a closer look at the position control module:

From the figure, there are three locations to publish setpoints to. The first being position setpoints to r_sp, the second being velocity setpoints which would be fed into the velocity feedforward path v_ff, and the third being acceleration setpoints fed to the acceleration feedforward path a_ff. The three Clover simpleoffboard functions capable of sending setpoints to these gateways are discussed:

The navigate function publishes position setpoints to r_sp, it does by publishing on the mavros/setpoint_position/local topic of type geometry_msgs/PoseStamped. It does it in a special way where it will take the speed from the user (0.5 m/s by default); all this does is set the slope of the position setpoints to allow the Clover to track the position at a relative speed rather then just sending a step input as done by the set_position function.

This assumes the user is not setting the yaw parameter (yaw=0 by default) or publishing a new value. If the user sets yaw = float('NaN') then yaw_rate is used (0 by default) which will publish the position and yaw_rate on the mavros/setpoint_raw/local topic of type mavros_msgs/PositionTarget.

set_position

The set_position function publishes setpoints to r_sp by publishing on the mavros/setpoint_position/local topic of type geometry_msgs/PoseStamped. Likewise, the handling of yaw and yaw_rate has the same influence here as it did with the navigate function. You can use this function in a while loop within a python script to publish position along a complex trajectory, however it is very limited as it only allows you to publish setpoints to r_sp whether a step input or a more complicated trajectory within a while loop using various equations. This is an issue because without feedforward control (using velocity, acceleration, etc..) PID control can only allow for relative tracking with the Clover and will lag behind the setpoints.

set_velocity

The set_velocity function publishes setpoints to v_ff by publishing on the mavros/setpoint_raw/local topic of type mavros_msgs/PositionTarget. Likewise, the handling of yaw and yaw_rate is similar to the set_position and navigate functions where yaw can be defined (yaw=0 by default) or set as yaw = float('NaN') then yaw_rate is used (0 by default). The set_velocity function is set to ignore position and acceleration setpoints therefore only velocity can be published in its current state.

The last two functions publish to the inner or low-level control module. A diagram illustrating these controllers can be found:

The above figure is what is tuned automatically when you follow the steps in the Auto-Tuning section.

set_attitude

A closer look at the Attitude controller can be seen:

It is a proportional controller with some nonlinear components to it. The set_attitude publishes to the quarternion setpoint q_sp by first sending roll, pitch, and yaw commands to the mavros/setpoint_attitude/attitude topic of type geometry_msgs/PoseStamped. This is eventually converted to a quarternion by PX4. The last setpoint provided is a thrust setpoint, this is normalized where 0 represents no throttle (propellers are stopped) and 1 represents full throttle. This is published on the mavros/setpoint_attitude/thrust topic of type mavros_msgs/thrust. Using this function is similar to operating in the Stabilized Mode.

set_rates

A closer look at the Rate controller can be seen:

From the figure, the Rate controller is a K-PID controller offering two configuration choices for PID (Standard and Parallel) with more information found in Rate Controller. The set_rates publishes to the rate setpoint Omega_sp by first sending roll_rate, pitch_rate, and yaw_rate commands to the mavros/setpoint_raw/attitude topic of type mavros_msgs/AttitudeTarget. Similar to the set_attitude function it publishes a normalized thrust setpoint where 0 represents no throttle (propellers are stopped) and 1 represents full throttle. This is through the same gateway at the rest of the rate commands where the function in simple_offboard ignores attitude setpoints. However if the user desired to send rate and attitude setpoints simultaneously, the set_rates function could easily be modified to do so. Using this function is similar to operating in the ACRO mode.

Setpoints must be given to PX4 at a rate of at least 2Hz or the Clover will go into failsafe mode, this sets the motors into safety mode where the Clover will mode likely glide into a fall. Preferably sending setpoints at 30 Hz or greater is desired for smooth trajectories. Clovers simple Offboard sends setpoints at 30 Hz.

Last updated