-
Notifications
You must be signed in to change notification settings - Fork 10
Bias Compensation
Freyja includes a bias compensation module that can determine external bias forces acting on the vehicle in-flight. These are usually time-varying factors (such as wind, a dynamic change in mass by dropping a payload etc), but can also be steady offsets (poorly leveled autopilot, incorrect total mass etc). The module is essentially a Luenberger/Kalman observer that runs parallel to the controller. The combination of the controller and observer is what makes the system an LQG system.
-
Controller parameter(s):
bias_compensation
: string"off" : no bias compensation/estimation at all
"on" : bias compensation is always on from the beginning (dangerous)
"auto" : bias compensation is automatically enabled/disabled based on flight mode- "off" keeps the estimator off at all times, and disallows turning it on using the service call (see below).
- "on" starts the estimator when the controller starts. This can be dangerous because if you switch in/out of computer mode, or if the vehicle is sitting on the ground, the estimator will accumulate biases. Generally speaking, this setting is recommended only if the entire mission is controlled end-to-end, i.e., no manual transitions. However, the estimator can be turned on/off mid-flight using a service call.
- "auto" will automatically turn on and reset the estimator upon mode transitions. However, this magic depends on communication from the autopilot to figure out if the flight mode corresponds to a Freyja-controlled mode or not; for instance,
/mavros/state
contains this information. This setting also allows turning it on/off mid-flight using a service call.
estimator_rate
: int
The rate at which the bias estimator thread is propagated. This will be influenced bycontroller_rate
parameter. -
Service call:
set_bias_compensation
:std_srvs/SetBool
"true" : turn bias compensation on
"false" : turn bias compensation offNote that the service will work only if
bias_compensation
is set to "on" or "auto". -
Estimator topics/debug:
- Topic
/controller_debug
:freyja_msgs/ControllerDebug
Contains a 4-vector that records the current biases (bn, be, bd
) that are currently known to the controller. The fourth element is foryaw
and is currently always zero. This topic is updated at the same rate as the controller is running. - Topic
/controller_debug
:freyja_msgs/ControllerDebug
Also contains aflags
variable which is a bit-field representation of the controller's internal state. See the message structure to find out which field corresponds to bias compensation. - Topic
/bias_estimates
:freyja_msgs/CurrentState
Contains estimator's outputs. The format of the state vector is:[pn, pe, pd, vn, ve, vd, bn, be, bd]
, where theb*
elements are the estimated acceleration biases in north, east and down (world-frame) axes. The rest of the elements in the vector are additional debug data.
- Topic
(c) aj, Nimbus Lab, 2020