2013-10-12 09:28:18 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
# include "AC_AttitudeControl.h"
2015-08-11 03:28:41 -03:00
# include <AP_HAL/AP_HAL.h>
# include <AP_Math/AP_Math.h>
2013-10-12 09:28:18 -03:00
// table of user settable parameters
const AP_Param : : GroupInfo AC_AttitudeControl : : var_info [ ] PROGMEM = {
2015-03-29 07:05:23 -03:00
// 0, 1 were RATE_RP_MAX, RATE_Y_MAX
2014-02-03 00:29:17 -04:00
// @Param: SLEW_YAW
// @DisplayName: Yaw target slew rate
// @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
2014-02-16 09:36:59 -04:00
// @Units: Centi-Degrees/Sec
2014-02-03 00:29:17 -04:00
// @Range: 500 18000
// @Increment: 100
// @User: Advanced
AP_GROUPINFO ( " SLEW_YAW " , 2 , AC_AttitudeControl , _slew_yaw , AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT ) ,
2013-10-12 09:28:18 -03:00
2015-02-11 08:10:56 -04:00
// 3 was for ACCEL_RP_MAX
2014-02-14 21:07:49 -04:00
// @Param: ACCEL_Y_MAX
// @DisplayName: Acceleration Max for Yaw
// @Description: Maximum acceleration in yaw axis
2014-02-16 09:36:59 -04:00
// @Units: Centi-Degrees/Sec/Sec
2014-07-17 04:22:32 -03:00
// @Range: 0 72000
// @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast
// @Increment: 1000
2014-02-14 21:07:49 -04:00
// @User: Advanced
2015-02-11 08:10:56 -04:00
AP_GROUPINFO ( " ACCEL_Y_MAX " , 4 , AC_AttitudeControl , _accel_yaw_max , AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT ) ,
2014-02-14 21:07:49 -04:00
2014-07-12 22:31:11 -03:00
// @Param: RATE_FF_ENAB
2014-06-06 02:04:06 -03:00
// @DisplayName: Rate Feedforward Enable
// @Description: Controls whether body-frame rate feedfoward is enabled or disabled
// @Values: 0:Disabled, 1:Enabled
// @User: Advanced
AP_GROUPINFO ( " RATE_FF_ENAB " , 5 , AC_AttitudeControl , _rate_bf_ff_enabled , AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT ) ,
2015-02-11 08:10:56 -04:00
// @Param: ACCEL_R_MAX
// @DisplayName: Acceleration Max for Roll
// @Description: Maximum acceleration in roll axis
// @Units: Centi-Degrees/Sec/Sec
// @Range: 0 180000
// @Increment: 1000
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
// @User: Advanced
AP_GROUPINFO ( " ACCEL_R_MAX " , 6 , AC_AttitudeControl , _accel_roll_max , AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT ) ,
// @Param: ACCEL_P_MAX
// @DisplayName: Acceleration Max for Pitch
// @Description: Maximum acceleration in pitch axis
// @Units: Centi-Degrees/Sec/Sec
// @Range: 0 180000
// @Increment: 1000
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
// @User: Advanced
AP_GROUPINFO ( " ACCEL_P_MAX " , 7 , AC_AttitudeControl , _accel_pitch_max , AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT ) ,
2013-10-12 09:28:18 -03:00
AP_GROUPEND
} ;
2014-01-11 04:02:42 -04:00
//
// high level controllers
//
2014-05-27 10:44:29 -03:00
void AC_AttitudeControl : : set_dt ( float delta_sec )
{
_dt = delta_sec ;
// set attitude controller's D term filters
2015-02-11 08:10:56 -04:00
_pid_rate_roll . set_dt ( _dt ) ;
_pid_rate_pitch . set_dt ( _dt ) ;
_pid_rate_yaw . set_dt ( _dt ) ;
2014-05-27 10:44:29 -03:00
}
2014-06-06 00:03:06 -03:00
// relax_bf_rate_controller - ensure body-frame rate controller has zero errors to relax rate controller output
void AC_AttitudeControl : : relax_bf_rate_controller ( )
2014-01-11 04:02:42 -04:00
{
2014-05-21 11:25:05 -03:00
// ensure zero error in body frame rate controllers
2014-07-13 04:48:30 -03:00
const Vector3f & gyro = _ahrs . get_gyro ( ) ;
2014-05-21 11:25:05 -03:00
_rate_bf_target = gyro * AC_ATTITUDE_CONTROL_DEGX100 ;
2015-07-27 04:37:10 -03:00
frame_conversion_bf_to_ef ( _rate_bf_target , _rate_ef_desired ) ;
2015-02-26 19:52:04 -04:00
_pid_rate_roll . reset_I ( ) ;
_pid_rate_pitch . reset_I ( ) ;
_pid_rate_yaw . reset_I ( ) ;
2014-01-11 04:02:42 -04:00
}
2015-06-23 04:49:12 -03:00
// shifts earth frame yaw target by yaw_shift_cd. yaw_shift_cd should be in centi-degreesa and is added to the current target heading
void AC_AttitudeControl : : shift_ef_yaw_target ( float yaw_shift_cd )
{
_angle_ef_target . z = wrap_360_cd_float ( _angle_ef_target . z + yaw_shift_cd ) ;
}
2014-02-09 22:59:51 -04:00
//
// methods to be called by upper controllers to request and implement a desired attitude
2014-02-19 02:55:45 -04:00
//
2014-02-19 04:05:29 -04:00
// angle_ef_roll_pitch_rate_ef_yaw_smooth - attempts to maintain a roll and pitch angle and yaw rate (all earth frame) while smoothing the attitude based on the feel parameter
// smoothing_gain : a number from 1 to 50 with 1 being sluggish and 50 being very crisp
void AC_AttitudeControl : : angle_ef_roll_pitch_rate_ef_yaw_smooth ( float roll_angle_ef , float pitch_angle_ef , float yaw_rate_ef , float smoothing_gain )
2014-02-19 02:55:45 -04:00
{
2015-02-11 08:10:56 -04:00
float rate_ef_desired ;
float rate_change_limit ;
2014-02-19 04:05:29 -04:00
Vector3f angle_ef_error ; // earth frame angle errors
// sanity check smoothing gain
smoothing_gain = constrain_float ( smoothing_gain , 1.0f , 50.0f ) ;
2015-03-04 08:16:42 -04:00
// if accel limiting and feed forward enabled
if ( ( _accel_roll_max > 0.0f ) & & _rate_bf_ff_enabled ) {
2015-02-11 08:10:56 -04:00
rate_change_limit = _accel_roll_max * _dt ;
2014-06-05 10:12:31 -03:00
2014-10-06 23:58:02 -03:00
// calculate earth-frame feed forward roll rate using linear response when close to the target, sqrt response when we're further away
2015-02-11 08:10:56 -04:00
rate_ef_desired = sqrt_controller ( roll_angle_ef - _angle_ef_target . x , smoothing_gain , _accel_roll_max ) ;
2014-10-06 23:58:02 -03:00
2014-10-07 00:00:04 -03:00
// apply acceleration limit to feed forward roll rate
_rate_ef_desired . x = constrain_float ( rate_ef_desired , _rate_ef_desired . x - rate_change_limit , _rate_ef_desired . x + rate_change_limit ) ;
2014-06-04 11:46:29 -03:00
2014-10-07 00:00:04 -03:00
// update earth-frame roll angle target using desired roll rate
2014-07-12 12:53:19 -03:00
update_ef_roll_angle_and_error ( _rate_ef_desired . x , angle_ef_error , AC_ATTITUDE_RATE_STAB_ROLL_OVERSHOOT_ANGLE_MAX ) ;
2015-02-11 08:10:56 -04:00
} else {
// target roll and pitch to desired input roll and pitch
_angle_ef_target . x = roll_angle_ef ;
angle_ef_error . x = wrap_180_cd_float ( _angle_ef_target . x - _ahrs . roll_sensor ) ;
// set roll and pitch feed forward to zero
_rate_ef_desired . x = 0 ;
}
// constrain earth-frame angle targets
_angle_ef_target . x = constrain_float ( _angle_ef_target . x , - _aparm . angle_max , _aparm . angle_max ) ;
2015-03-04 08:16:42 -04:00
// if accel limiting and feed forward enabled
if ( ( _accel_pitch_max > 0.0f ) & & _rate_bf_ff_enabled ) {
2015-02-11 08:10:56 -04:00
rate_change_limit = _accel_pitch_max * _dt ;
2014-06-04 11:46:29 -03:00
2014-10-06 23:58:02 -03:00
// calculate earth-frame feed forward pitch rate using linear response when close to the target, sqrt response when we're further away
2015-02-11 08:10:56 -04:00
rate_ef_desired = sqrt_controller ( pitch_angle_ef - _angle_ef_target . y , smoothing_gain , _accel_pitch_max ) ;
2014-10-06 23:58:02 -03:00
2014-10-07 00:00:04 -03:00
// apply acceleration limit to feed forward pitch rate
_rate_ef_desired . y = constrain_float ( rate_ef_desired , _rate_ef_desired . y - rate_change_limit , _rate_ef_desired . y + rate_change_limit ) ;
2014-06-04 11:46:29 -03:00
2014-10-07 00:00:04 -03:00
// update earth-frame pitch angle target using desired pitch rate
2014-07-12 12:53:19 -03:00
update_ef_pitch_angle_and_error ( _rate_ef_desired . y , angle_ef_error , AC_ATTITUDE_RATE_STAB_PITCH_OVERSHOOT_ANGLE_MAX ) ;
2014-02-19 02:55:45 -04:00
} else {
2014-06-04 11:46:29 -03:00
// target roll and pitch to desired input roll and pitch
2014-10-07 00:00:04 -03:00
_angle_ef_target . y = pitch_angle_ef ;
2014-06-05 10:12:31 -03:00
angle_ef_error . y = wrap_180_cd_float ( _angle_ef_target . y - _ahrs . pitch_sensor ) ;
2014-06-04 11:46:29 -03:00
// set roll and pitch feed forward to zero
2014-10-07 00:00:04 -03:00
_rate_ef_desired . y = 0 ;
2014-02-19 02:55:45 -04:00
}
2014-07-12 08:46:13 -03:00
// constrain earth-frame angle targets
_angle_ef_target . y = constrain_float ( _angle_ef_target . y , - _aparm . angle_max , _aparm . angle_max ) ;
2014-02-19 04:05:29 -04:00
2015-02-11 08:10:56 -04:00
if ( _accel_yaw_max > 0.0f ) {
2014-10-07 00:00:04 -03:00
// set earth-frame feed forward rate for yaw
2015-02-11 08:10:56 -04:00
rate_change_limit = _accel_yaw_max * _dt ;
2014-10-07 00:00:04 -03:00
2015-02-11 08:10:56 -04:00
// update yaw rate target with acceleration limit
2014-10-07 00:00:04 -03:00
_rate_ef_desired . z + = constrain_float ( yaw_rate_ef - _rate_ef_desired . z , - rate_change_limit , rate_change_limit ) ;
2014-02-19 02:55:45 -04:00
2014-06-04 11:46:29 -03:00
// calculate yaw target angle and angle error
2014-07-12 12:53:19 -03:00
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX ) ;
2014-02-19 02:55:45 -04:00
} else {
2014-06-04 11:46:29 -03:00
// set yaw feed forward to zero
2014-10-07 00:00:04 -03:00
_rate_ef_desired . z = yaw_rate_ef ;
2014-06-04 11:46:29 -03:00
// calculate yaw target angle and angle error
2014-07-12 12:53:19 -03:00
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX ) ;
2014-02-19 02:55:45 -04:00
}
// convert earth-frame angle errors to body-frame angle errors
frame_conversion_ef_to_bf ( angle_ef_error , _angle_bf_error ) ;
// convert body-frame angle errors to body-frame rate targets
update_rate_bf_targets ( ) ;
// add body frame rate feed forward
2014-06-06 02:04:06 -03:00
if ( _rate_bf_ff_enabled ) {
2014-07-12 08:46:13 -03:00
// convert earth-frame feed forward rates to body-frame feed forward rates
frame_conversion_ef_to_bf ( _rate_ef_desired , _rate_bf_desired ) ;
_rate_bf_target + = _rate_bf_desired ;
} else {
// convert earth-frame feed forward rates to body-frame feed forward rates
2014-07-16 09:50:31 -03:00
frame_conversion_ef_to_bf ( Vector3f ( 0 , 0 , _rate_ef_desired . z ) , _rate_bf_desired ) ;
2014-06-06 02:04:06 -03:00
_rate_bf_target + = _rate_bf_desired ;
}
2014-02-19 02:55:45 -04:00
// body-frame to motor outputs should be called separately
}
//
// methods to be called by upper controllers to request and implement a desired attitude
2014-02-09 22:59:51 -04:00
//
2014-02-13 22:52:58 -04:00
// angle_ef_roll_pitch_rate_ef_yaw - attempts to maintain a roll and pitch angle and yaw rate (all earth frame)
void AC_AttitudeControl : : angle_ef_roll_pitch_rate_ef_yaw ( float roll_angle_ef , float pitch_angle_ef , float yaw_rate_ef )
2014-01-11 04:02:42 -04:00
{
2014-02-09 22:59:51 -04:00
Vector3f angle_ef_error ; // earth frame angle errors
2014-02-13 22:52:58 -04:00
2014-02-09 22:59:51 -04:00
// set earth-frame angle targets for roll and pitch and calculate angle error
2014-07-12 08:46:13 -03:00
_angle_ef_target . x = constrain_float ( roll_angle_ef , - _aparm . angle_max , _aparm . angle_max ) ;
2014-02-09 22:59:51 -04:00
angle_ef_error . x = wrap_180_cd_float ( _angle_ef_target . x - _ahrs . roll_sensor ) ;
2014-07-12 08:46:13 -03:00
_angle_ef_target . y = constrain_float ( pitch_angle_ef , - _aparm . angle_max , _aparm . angle_max ) ;
2014-02-09 22:59:51 -04:00
angle_ef_error . y = wrap_180_cd_float ( _angle_ef_target . y - _ahrs . pitch_sensor ) ;
2014-01-11 04:02:42 -04:00
2015-02-11 08:10:56 -04:00
if ( _accel_yaw_max > 0.0f ) {
2014-06-07 02:27:39 -03:00
// set earth-frame feed forward rate for yaw
2015-02-11 08:10:56 -04:00
float rate_change_limit = _accel_yaw_max * _dt ;
2014-02-13 22:52:58 -04:00
2014-06-07 02:27:39 -03:00
float rate_change = yaw_rate_ef - _rate_ef_desired . z ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_ef_desired . z + = rate_change ;
// calculate yaw target angle and angle error
2014-07-12 12:53:19 -03:00
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX ) ;
2014-06-07 02:27:39 -03:00
} else {
// set yaw feed forward to zero
2014-07-12 08:46:13 -03:00
_rate_ef_desired . z = yaw_rate_ef ;
2014-06-07 02:27:39 -03:00
// calculate yaw target angle and angle error
2014-07-12 12:53:19 -03:00
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX ) ;
2014-06-07 02:27:39 -03:00
}
2014-01-11 04:02:42 -04:00
2014-02-09 22:59:51 -04:00
// convert earth-frame angle errors to body-frame angle errors
2014-02-13 22:52:58 -04:00
frame_conversion_ef_to_bf ( angle_ef_error , _angle_bf_error ) ;
2014-01-11 04:02:42 -04:00
2014-02-09 22:59:51 -04:00
// convert body-frame angle errors to body-frame rate targets
2014-02-13 22:52:58 -04:00
update_rate_bf_targets ( ) ;
2014-01-11 04:02:42 -04:00
2014-07-12 08:46:13 -03:00
// set roll and pitch feed forward to zero
_rate_ef_desired . x = 0 ;
_rate_ef_desired . y = 0 ;
// convert earth-frame feed forward rates to body-frame feed forward rates
frame_conversion_ef_to_bf ( _rate_ef_desired , _rate_bf_desired ) ;
_rate_bf_target + = _rate_bf_desired ;
2014-01-11 04:02:42 -04:00
// body-frame to motor outputs should be called separately
}
2014-02-13 22:52:58 -04:00
// angle_ef_roll_pitch_yaw - attempts to maintain a roll, pitch and yaw angle (all earth frame)
2014-02-09 22:59:51 -04:00
// if yaw_slew is true then target yaw movement will be gradually moved to the new target based on the SLEW_YAW parameter
2014-02-13 22:52:58 -04:00
void AC_AttitudeControl : : angle_ef_roll_pitch_yaw ( float roll_angle_ef , float pitch_angle_ef , float yaw_angle_ef , bool slew_yaw )
2014-01-28 04:30:33 -04:00
{
2014-02-09 22:59:51 -04:00
Vector3f angle_ef_error ;
2014-01-28 04:30:33 -04:00
2014-01-24 22:59:48 -04:00
// set earth-frame angle targets
2014-06-06 00:59:16 -03:00
_angle_ef_target . x = constrain_float ( roll_angle_ef , - _aparm . angle_max , _aparm . angle_max ) ;
_angle_ef_target . y = constrain_float ( pitch_angle_ef , - _aparm . angle_max , _aparm . angle_max ) ;
2014-02-09 22:59:51 -04:00
_angle_ef_target . z = yaw_angle_ef ;
2014-01-24 22:59:48 -04:00
2014-02-09 22:59:51 -04:00
// calculate earth frame errors
angle_ef_error . x = wrap_180_cd_float ( _angle_ef_target . x - _ahrs . roll_sensor ) ;
angle_ef_error . y = wrap_180_cd_float ( _angle_ef_target . y - _ahrs . pitch_sensor ) ;
angle_ef_error . z = wrap_180_cd_float ( _angle_ef_target . z - _ahrs . yaw_sensor ) ;
2013-10-12 09:28:18 -03:00
2014-03-29 08:41:22 -03:00
// constrain the yaw angle error
if ( slew_yaw ) {
angle_ef_error . z = constrain_float ( angle_ef_error . z , - _slew_yaw , _slew_yaw ) ;
}
2014-02-09 22:59:51 -04:00
// convert earth-frame angle errors to body-frame angle errors
2014-02-13 22:52:58 -04:00
frame_conversion_ef_to_bf ( angle_ef_error , _angle_bf_error ) ;
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
// convert body-frame angle errors to body-frame rate targets
2014-02-13 22:52:58 -04:00
update_rate_bf_targets ( ) ;
2014-02-01 02:27:58 -04:00
2014-02-09 22:59:51 -04:00
// body-frame to motor outputs should be called separately
2013-10-12 09:28:18 -03:00
}
2014-02-13 22:52:58 -04:00
// rate_ef_roll_pitch_yaw - attempts to maintain a roll, pitch and yaw rate (all earth frame)
void AC_AttitudeControl : : rate_ef_roll_pitch_yaw ( float roll_rate_ef , float pitch_rate_ef , float yaw_rate_ef )
2013-10-12 09:28:18 -03:00
{
2014-02-14 21:07:49 -04:00
Vector3f angle_ef_error ;
2014-07-12 08:46:13 -03:00
float rate_change_limit , rate_change ;
2014-02-14 21:07:49 -04:00
2015-02-11 08:10:56 -04:00
if ( _accel_roll_max > 0.0f ) {
rate_change_limit = _accel_roll_max * _dt ;
2014-02-14 21:07:49 -04:00
2014-07-12 08:46:13 -03:00
// update feed forward roll rate after checking it is within acceleration limits
rate_change = roll_rate_ef - _rate_ef_desired . x ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_ef_desired . x + = rate_change ;
2015-02-11 08:10:56 -04:00
} else {
_rate_ef_desired . x = roll_rate_ef ;
}
if ( _accel_pitch_max > 0.0f ) {
rate_change_limit = _accel_pitch_max * _dt ;
2013-10-12 09:28:18 -03:00
2014-07-12 08:46:13 -03:00
// update feed forward pitch rate after checking it is within acceleration limits
rate_change = pitch_rate_ef - _rate_ef_desired . y ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_ef_desired . y + = rate_change ;
} else {
_rate_ef_desired . y = pitch_rate_ef ;
}
2015-02-11 08:10:56 -04:00
if ( _accel_yaw_max > 0.0f ) {
rate_change_limit = _accel_yaw_max * _dt ;
2014-07-12 08:46:13 -03:00
// update feed forward yaw rate after checking it is within acceleration limits
rate_change = yaw_rate_ef - _rate_ef_desired . z ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_ef_desired . z + = rate_change ;
} else {
_rate_ef_desired . z = yaw_rate_ef ;
}
2013-10-12 09:28:18 -03:00
2014-02-13 22:52:58 -04:00
// update earth frame angle targets and errors
2014-07-12 12:53:19 -03:00
update_ef_roll_angle_and_error ( _rate_ef_desired . x , angle_ef_error , AC_ATTITUDE_RATE_STAB_ROLL_OVERSHOOT_ANGLE_MAX ) ;
update_ef_pitch_angle_and_error ( _rate_ef_desired . y , angle_ef_error , AC_ATTITUDE_RATE_STAB_PITCH_OVERSHOOT_ANGLE_MAX ) ;
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_YAW_OVERSHOOT_ANGLE_MAX ) ;
2014-02-09 22:59:51 -04:00
2014-06-06 00:59:16 -03:00
// constrain earth-frame angle targets
_angle_ef_target . x = constrain_float ( _angle_ef_target . x , - _aparm . angle_max , _aparm . angle_max ) ;
_angle_ef_target . y = constrain_float ( _angle_ef_target . y , - _aparm . angle_max , _aparm . angle_max ) ;
2014-02-09 22:59:51 -04:00
// convert earth-frame angle errors to body-frame angle errors
2014-02-13 22:52:58 -04:00
frame_conversion_ef_to_bf ( angle_ef_error , _angle_bf_error ) ;
2014-02-09 22:59:51 -04:00
// convert body-frame angle errors to body-frame rate targets
2014-02-13 22:52:58 -04:00
update_rate_bf_targets ( ) ;
2014-02-09 22:59:51 -04:00
2014-07-12 08:46:13 -03:00
// convert earth-frame rates to body-frame rates
frame_conversion_ef_to_bf ( _rate_ef_desired , _rate_bf_desired ) ;
2014-02-09 22:59:51 -04:00
// add body frame rate feed forward
2014-07-12 08:46:13 -03:00
_rate_bf_target + = _rate_bf_desired ;
2014-02-09 22:59:51 -04:00
// body-frame to motor outputs should be called separately
2013-10-12 09:28:18 -03:00
}
2014-02-13 22:52:58 -04:00
// rate_bf_roll_pitch_yaw - attempts to maintain a roll, pitch and yaw rate (all body frame)
void AC_AttitudeControl : : rate_bf_roll_pitch_yaw ( float roll_rate_bf , float pitch_rate_bf , float yaw_rate_bf )
2013-10-12 09:28:18 -03:00
{
2014-02-13 08:34:27 -04:00
Vector3f angle_ef_error ;
2014-02-13 22:52:58 -04:00
2014-08-05 08:59:25 -03:00
float rate_change , rate_change_limit ;
// update the rate feed forward with angular acceleration limits
2015-02-11 08:10:56 -04:00
if ( _accel_roll_max > 0.0f ) {
rate_change_limit = _accel_roll_max * _dt ;
2014-08-05 08:59:25 -03:00
2015-02-11 08:10:56 -04:00
rate_change = roll_rate_bf - _rate_bf_desired . x ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_bf_desired . x + = rate_change ;
} else {
_rate_bf_desired . x = roll_rate_bf ;
}
// update the rate feed forward with angular acceleration limits
if ( _accel_pitch_max > 0.0f ) {
rate_change_limit = _accel_pitch_max * _dt ;
2014-08-05 08:59:25 -03:00
2015-02-11 08:10:56 -04:00
rate_change = pitch_rate_bf - _rate_bf_desired . y ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_bf_desired . y + = rate_change ;
2014-08-05 08:59:25 -03:00
} else {
2015-02-11 08:10:56 -04:00
_rate_bf_desired . y = pitch_rate_bf ;
2014-08-05 08:59:25 -03:00
}
2015-02-11 08:10:56 -04:00
if ( _accel_yaw_max > 0.0f ) {
rate_change_limit = _accel_yaw_max * _dt ;
2014-08-05 08:59:25 -03:00
rate_change = yaw_rate_bf - _rate_bf_desired . z ;
rate_change = constrain_float ( rate_change , - rate_change_limit , rate_change_limit ) ;
_rate_bf_desired . z + = rate_change ;
} else {
_rate_bf_desired . z = yaw_rate_bf ;
}
2014-02-09 22:59:51 -04:00
// Update angle error
2014-06-06 00:51:35 -03:00
if ( labs ( _ahrs . pitch_sensor ) < _acro_angle_switch ) {
2014-02-13 08:34:27 -04:00
_acro_angle_switch = 6000 ;
// convert body-frame rates to earth-frame rates
2014-02-14 21:07:49 -04:00
frame_conversion_bf_to_ef ( _rate_bf_desired , _rate_ef_desired ) ;
2014-02-13 22:52:58 -04:00
// update earth frame angle targets and errors
2014-07-12 12:53:19 -03:00
update_ef_roll_angle_and_error ( _rate_ef_desired . x , angle_ef_error , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
update_ef_pitch_angle_and_error ( _rate_ef_desired . y , angle_ef_error , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
update_ef_yaw_angle_and_error ( _rate_ef_desired . z , angle_ef_error , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
2014-02-13 08:34:27 -04:00
// convert earth-frame angle errors to body-frame angle errors
2014-02-13 22:52:58 -04:00
frame_conversion_ef_to_bf ( angle_ef_error , _angle_bf_error ) ;
2014-02-13 08:34:27 -04:00
} else {
_acro_angle_switch = 4500 ;
2014-02-13 22:52:58 -04:00
integrate_bf_rate_error_to_angle_errors ( ) ;
2014-08-22 10:50:10 -03:00
if ( frame_conversion_bf_to_ef ( _angle_bf_error , angle_ef_error ) ) {
_angle_ef_target . x = wrap_180_cd_float ( angle_ef_error . x + _ahrs . roll_sensor ) ;
_angle_ef_target . y = wrap_180_cd_float ( angle_ef_error . y + _ahrs . pitch_sensor ) ;
_angle_ef_target . z = wrap_360_cd_float ( angle_ef_error . z + _ahrs . yaw_sensor ) ;
}
2014-06-06 00:51:35 -03:00
if ( _angle_ef_target . y > 9000.0f ) {
_angle_ef_target . x = wrap_180_cd_float ( _angle_ef_target . x + 18000.0f ) ;
2014-08-23 09:42:23 -03:00
_angle_ef_target . y = wrap_180_cd_float ( 18000.0f - _angle_ef_target . y ) ;
2014-06-06 00:51:35 -03:00
_angle_ef_target . z = wrap_360_cd_float ( _angle_ef_target . z + 18000.0f ) ;
2014-02-13 08:34:27 -04:00
}
2014-06-06 00:51:35 -03:00
if ( _angle_ef_target . y < - 9000.0f ) {
_angle_ef_target . x = wrap_180_cd_float ( _angle_ef_target . x + 18000.0f ) ;
2014-08-23 09:42:23 -03:00
_angle_ef_target . y = wrap_180_cd_float ( - 18000.0f - _angle_ef_target . y ) ;
2014-06-06 00:51:35 -03:00
_angle_ef_target . z = wrap_360_cd_float ( _angle_ef_target . z + 18000.0f ) ;
2014-02-13 08:34:27 -04:00
}
}
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
// convert body-frame angle errors to body-frame rate targets
2014-02-13 22:52:58 -04:00
update_rate_bf_targets ( ) ;
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
// body-frame rate commands added
2014-07-12 08:46:13 -03:00
_rate_bf_target + = _rate_bf_desired ;
2014-02-09 22:59:51 -04:00
}
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
//
// rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
// should be called at 100hz or more
//
void AC_AttitudeControl : : rate_controller_run ( )
{
// call rate controllers and send output to motors object
// To-Do: should the outputs from get_rate_roll, pitch, yaw be int16_t which is the input to the motors library?
// To-Do: skip this step if the throttle out is zero?
2014-02-10 00:23:52 -04:00
_motors . set_roll ( rate_bf_to_motor_roll ( _rate_bf_target . x ) ) ;
_motors . set_pitch ( rate_bf_to_motor_pitch ( _rate_bf_target . y ) ) ;
_motors . set_yaw ( rate_bf_to_motor_yaw ( _rate_bf_target . z ) ) ;
2013-10-12 09:28:18 -03:00
}
//
2014-02-09 22:59:51 -04:00
// earth-frame <-> body-frame conversion functions
2013-10-12 09:28:18 -03:00
//
2014-02-13 22:52:58 -04:00
// frame_conversion_ef_to_bf - converts earth frame vector to body frame vector
void AC_AttitudeControl : : frame_conversion_ef_to_bf ( const Vector3f & ef_vector , Vector3f & bf_vector )
2014-02-09 22:59:51 -04:00
{
// convert earth frame rates to body frame rates
2014-02-13 22:52:58 -04:00
bf_vector . x = ef_vector . x - _ahrs . sin_pitch ( ) * ef_vector . z ;
bf_vector . y = _ahrs . cos_roll ( ) * ef_vector . y + _ahrs . sin_roll ( ) * _ahrs . cos_pitch ( ) * ef_vector . z ;
bf_vector . z = - _ahrs . sin_roll ( ) * ef_vector . y + _ahrs . cos_pitch ( ) * _ahrs . cos_roll ( ) * ef_vector . z ;
2014-02-09 22:59:51 -04:00
}
2014-02-13 22:52:58 -04:00
// frame_conversion_bf_to_ef - converts body frame vector to earth frame vector
2014-08-22 10:50:10 -03:00
bool AC_AttitudeControl : : frame_conversion_bf_to_ef ( const Vector3f & bf_vector , Vector3f & ef_vector )
2014-02-09 22:59:51 -04:00
{
2014-08-22 10:50:10 -03:00
// avoid divide by zero
2015-05-04 23:34:37 -03:00
if ( is_zero ( _ahrs . cos_pitch ( ) ) ) {
2014-08-22 10:50:10 -03:00
return false ;
}
// convert earth frame angle or rates to body frame
2014-02-13 22:52:58 -04:00
ef_vector . x = bf_vector . x + _ahrs . sin_roll ( ) * ( _ahrs . sin_pitch ( ) / _ahrs . cos_pitch ( ) ) * bf_vector . y + _ahrs . cos_roll ( ) * ( _ahrs . sin_pitch ( ) / _ahrs . cos_pitch ( ) ) * bf_vector . z ;
ef_vector . y = _ahrs . cos_roll ( ) * bf_vector . y - _ahrs . sin_roll ( ) * bf_vector . z ;
ef_vector . z = ( _ahrs . sin_roll ( ) / _ahrs . cos_pitch ( ) ) * bf_vector . y + ( _ahrs . cos_roll ( ) / _ahrs . cos_pitch ( ) ) * bf_vector . z ;
2014-08-22 10:50:10 -03:00
return true ;
2014-02-09 22:59:51 -04:00
}
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
//
// protected methods
//
2014-01-24 22:59:48 -04:00
2014-02-09 22:59:51 -04:00
//
// stabilized rate controller (body-frame) methods
//
2014-02-13 22:52:58 -04:00
// update_ef_roll_angle_and_error - update _angle_ef_target.x using an earth frame roll rate request
2014-07-12 12:53:19 -03:00
void AC_AttitudeControl : : update_ef_roll_angle_and_error ( float roll_rate_ef , Vector3f & angle_ef_error , float overshoot_max )
2014-02-13 08:34:27 -04:00
{
// calculate angle error with maximum of +- max angle overshoot
angle_ef_error . x = wrap_180_cd ( _angle_ef_target . x - _ahrs . roll_sensor ) ;
2014-07-12 12:53:19 -03:00
angle_ef_error . x = constrain_float ( angle_ef_error . x , - overshoot_max , overshoot_max ) ;
2014-02-13 08:34:27 -04:00
// update roll angle target to be within max angle overshoot of our roll angle
2014-02-19 04:05:29 -04:00
_angle_ef_target . x = angle_ef_error . x + _ahrs . roll_sensor ;
// increment the roll angle target
_angle_ef_target . x + = roll_rate_ef * _dt ;
_angle_ef_target . x = wrap_180_cd ( _angle_ef_target . x ) ;
2014-02-13 08:34:27 -04:00
}
2014-02-13 22:52:58 -04:00
// update_ef_pitch_angle_and_error - update _angle_ef_target.y using an earth frame pitch rate request
2014-07-12 12:53:19 -03:00
void AC_AttitudeControl : : update_ef_pitch_angle_and_error ( float pitch_rate_ef , Vector3f & angle_ef_error , float overshoot_max )
2014-02-13 08:34:27 -04:00
{
// calculate angle error with maximum of +- max angle overshoot
// To-Do: should we do something better as we cross 90 degrees?
angle_ef_error . y = wrap_180_cd ( _angle_ef_target . y - _ahrs . pitch_sensor ) ;
2014-07-12 12:53:19 -03:00
angle_ef_error . y = constrain_float ( angle_ef_error . y , - overshoot_max , overshoot_max ) ;
2014-02-13 08:34:27 -04:00
// update pitch angle target to be within max angle overshoot of our pitch angle
2014-02-19 04:05:29 -04:00
_angle_ef_target . y = angle_ef_error . y + _ahrs . pitch_sensor ;
// increment the pitch angle target
_angle_ef_target . y + = pitch_rate_ef * _dt ;
_angle_ef_target . y = wrap_180_cd ( _angle_ef_target . y ) ;
2014-02-13 08:34:27 -04:00
}
2014-02-13 22:52:58 -04:00
// update_ef_yaw_angle_and_error - update _angle_ef_target.z using an earth frame yaw rate request
2014-07-12 12:53:19 -03:00
void AC_AttitudeControl : : update_ef_yaw_angle_and_error ( float yaw_rate_ef , Vector3f & angle_ef_error , float overshoot_max )
2014-02-13 08:34:27 -04:00
{
// calculate angle error with maximum of +- max angle overshoot
angle_ef_error . z = wrap_180_cd ( _angle_ef_target . z - _ahrs . yaw_sensor ) ;
2014-07-12 12:53:19 -03:00
angle_ef_error . z = constrain_float ( angle_ef_error . z , - overshoot_max , overshoot_max ) ;
2014-02-13 08:34:27 -04:00
// update yaw angle target to be within max angle overshoot of our current heading
2014-02-19 04:05:29 -04:00
_angle_ef_target . z = angle_ef_error . z + _ahrs . yaw_sensor ;
// increment the yaw angle target
_angle_ef_target . z + = yaw_rate_ef * _dt ;
_angle_ef_target . z = wrap_360_cd ( _angle_ef_target . z ) ;
2014-02-13 08:34:27 -04:00
}
2014-02-13 22:52:58 -04:00
// update_rate_bf_errors - calculates body frame angle errors
2014-02-09 22:59:51 -04:00
// body-frame feed forward rates (centi-degrees / second) taken from _angle_bf_error
// angle errors in centi-degrees placed in _angle_bf_error
2014-02-13 22:52:58 -04:00
void AC_AttitudeControl : : integrate_bf_rate_error_to_angle_errors ( )
2014-01-24 22:59:48 -04:00
{
// roll - calculate body-frame angle error by integrating body-frame rate error
2014-07-13 04:48:30 -03:00
_angle_bf_error . x + = ( _rate_bf_desired . x - ( _ahrs . get_gyro ( ) . x * AC_ATTITUDE_CONTROL_DEGX100 ) ) * _dt ;
2014-01-24 22:59:48 -04:00
// roll - limit maximum error
2014-07-12 12:53:19 -03:00
_angle_bf_error . x = constrain_float ( _angle_bf_error . x , - AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
2014-01-24 22:59:48 -04:00
// pitch - calculate body-frame angle error by integrating body-frame rate error
2014-07-13 04:48:30 -03:00
_angle_bf_error . y + = ( _rate_bf_desired . y - ( _ahrs . get_gyro ( ) . y * AC_ATTITUDE_CONTROL_DEGX100 ) ) * _dt ;
2014-01-24 22:59:48 -04:00
// pitch - limit maximum error
2014-07-12 12:53:19 -03:00
_angle_bf_error . y = constrain_float ( _angle_bf_error . y , - AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
2014-01-24 22:59:48 -04:00
// yaw - calculate body-frame angle error by integrating body-frame rate error
2014-07-13 04:48:30 -03:00
_angle_bf_error . z + = ( _rate_bf_desired . z - ( _ahrs . get_gyro ( ) . z * AC_ATTITUDE_CONTROL_DEGX100 ) ) * _dt ;
2014-01-24 22:59:48 -04:00
// yaw - limit maximum error
2014-07-12 12:53:19 -03:00
_angle_bf_error . z = constrain_float ( _angle_bf_error . z , - AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX , AC_ATTITUDE_RATE_STAB_ACRO_OVERSHOOT_ANGLE_MAX ) ;
2014-01-24 22:59:48 -04:00
2015-05-19 10:55:40 -03:00
// To-Do: handle case of motors being disarmed or channel_throttle == 0 and set error to zero
2014-01-24 22:59:48 -04:00
}
2013-10-12 09:28:18 -03:00
2014-02-13 22:52:58 -04:00
// update_rate_bf_targets - converts body-frame angle error to body-frame rate targets for roll, pitch and yaw axis
2014-02-09 22:59:51 -04:00
// targets rates in centi-degrees taken from _angle_bf_error
// results in centi-degrees/sec put into _rate_bf_target
2014-02-13 22:52:58 -04:00
void AC_AttitudeControl : : update_rate_bf_targets ( )
2013-10-12 09:28:18 -03:00
{
2015-03-29 07:05:23 -03:00
2014-02-09 22:59:51 -04:00
// stab roll calculation
// constrain roll rate request
if ( _flags . limit_angle_to_rate_request ) {
2015-03-29 07:05:23 -03:00
_rate_bf_target . x = sqrt_controller ( _angle_bf_error . x , _p_angle_roll . kP ( ) , constrain_float ( _accel_roll_max / 2.0f , AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN , AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX ) ) ;
} else {
_rate_bf_target . x = _p_angle_roll . kP ( ) * _angle_bf_error . x ;
2014-02-09 22:59:51 -04:00
}
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
// stab pitch calculation
// constrain pitch rate request
if ( _flags . limit_angle_to_rate_request ) {
2015-03-29 07:05:23 -03:00
_rate_bf_target . y = sqrt_controller ( _angle_bf_error . y , _p_angle_pitch . kP ( ) , constrain_float ( _accel_pitch_max / 2.0f , AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN , AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX ) ) ;
} else {
_rate_bf_target . y = _p_angle_pitch . kP ( ) * _angle_bf_error . y ;
2014-02-09 22:59:51 -04:00
}
2013-10-12 09:28:18 -03:00
2014-02-09 22:59:51 -04:00
// stab yaw calculation
// constrain yaw rate request
if ( _flags . limit_angle_to_rate_request ) {
2015-03-29 07:05:23 -03:00
_rate_bf_target . z = sqrt_controller ( _angle_bf_error . z , _p_angle_yaw . kP ( ) , constrain_float ( _accel_yaw_max / 2.0f , AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN , AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX ) ) ;
} else {
_rate_bf_target . z = _p_angle_yaw . kP ( ) * _angle_bf_error . z ;
2014-02-09 22:59:51 -04:00
}
2014-05-31 21:50:25 -03:00
2015-04-14 10:01:11 -03:00
// include roll and pitch rate required to account for precession of the desired attitude about the body frame yaw axes
2014-08-05 09:00:24 -03:00
_rate_bf_target . x + = _angle_bf_error . y * _ahrs . get_gyro ( ) . z ;
_rate_bf_target . y + = - _angle_bf_error . x * _ahrs . get_gyro ( ) . z ;
2013-10-12 09:28:18 -03:00
}
//
// body-frame rate controller
//
// rate_bf_to_motor_roll - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
float AC_AttitudeControl : : rate_bf_to_motor_roll ( float rate_target_cds )
{
float p , i , d ; // used to capture pid values for logging
float current_rate ; // this iteration's rate
float rate_error ; // simply target_rate - current_rate
// get current rate
// To-Do: make getting gyro rates more efficient?
2014-07-13 04:48:30 -03:00
current_rate = ( _ahrs . get_gyro ( ) . x * AC_ATTITUDE_CONTROL_DEGX100 ) ;
2013-10-12 09:28:18 -03:00
// calculate error and call pid controller
rate_error = rate_target_cds - current_rate ;
2015-02-11 08:10:56 -04:00
_pid_rate_roll . set_input_filter_d ( rate_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_roll . set_desired_rate ( rate_target_cds ) ;
2015-02-11 08:10:56 -04:00
// get p value
p = _pid_rate_roll . get_p ( ) ;
2013-10-12 09:28:18 -03:00
// get i term
i = _pid_rate_roll . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
if ( ! _motors . limit . roll_pitch | | ( ( i > 0 & & rate_error < 0 ) | | ( i < 0 & & rate_error > 0 ) ) ) {
2015-02-11 08:10:56 -04:00
i = _pid_rate_roll . get_i ( ) ;
2013-10-12 09:28:18 -03:00
}
// get d term
2015-02-11 08:10:56 -04:00
d = _pid_rate_roll . get_d ( ) ;
2013-10-12 09:28:18 -03:00
// constrain output and return
return constrain_float ( ( p + i + d ) , - AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) ;
}
// rate_bf_to_motor_pitch - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
float AC_AttitudeControl : : rate_bf_to_motor_pitch ( float rate_target_cds )
{
float p , i , d ; // used to capture pid values for logging
float current_rate ; // this iteration's rate
float rate_error ; // simply target_rate - current_rate
// get current rate
// To-Do: make getting gyro rates more efficient?
2014-07-13 04:48:30 -03:00
current_rate = ( _ahrs . get_gyro ( ) . y * AC_ATTITUDE_CONTROL_DEGX100 ) ;
2013-10-12 09:28:18 -03:00
// calculate error and call pid controller
rate_error = rate_target_cds - current_rate ;
2015-02-11 08:10:56 -04:00
_pid_rate_pitch . set_input_filter_d ( rate_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_pitch . set_desired_rate ( rate_target_cds ) ;
2015-02-11 08:10:56 -04:00
// get p value
p = _pid_rate_pitch . get_p ( ) ;
2013-10-12 09:28:18 -03:00
// get i term
i = _pid_rate_pitch . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
if ( ! _motors . limit . roll_pitch | | ( ( i > 0 & & rate_error < 0 ) | | ( i < 0 & & rate_error > 0 ) ) ) {
2015-02-11 08:10:56 -04:00
i = _pid_rate_pitch . get_i ( ) ;
2013-10-12 09:28:18 -03:00
}
// get d term
2015-02-11 08:10:56 -04:00
d = _pid_rate_pitch . get_d ( ) ;
2013-10-12 09:28:18 -03:00
// constrain output and return
return constrain_float ( ( p + i + d ) , - AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX ) ;
}
// rate_bf_to_motor_yaw - ask the rate controller to calculate the motor outputs to achieve the target rate in centi-degrees / second
float AC_AttitudeControl : : rate_bf_to_motor_yaw ( float rate_target_cds )
{
float p , i , d ; // used to capture pid values for logging
float current_rate ; // this iteration's rate
float rate_error ; // simply target_rate - current_rate
// get current rate
// To-Do: make getting gyro rates more efficient?
2014-07-13 04:48:30 -03:00
current_rate = ( _ahrs . get_gyro ( ) . z * AC_ATTITUDE_CONTROL_DEGX100 ) ;
2013-10-12 09:28:18 -03:00
// calculate error and call pid controller
rate_error = rate_target_cds - current_rate ;
2015-02-11 08:10:56 -04:00
_pid_rate_yaw . set_input_filter_all ( rate_error ) ;
2015-05-24 02:52:44 -03:00
_pid_rate_yaw . set_desired_rate ( rate_target_cds ) ;
2015-02-11 08:07:47 -04:00
// get p value
2015-02-11 08:10:56 -04:00
p = _pid_rate_yaw . get_p ( ) ;
2013-10-12 09:28:18 -03:00
// get i term
i = _pid_rate_yaw . get_integrator ( ) ;
// update i term as long as we haven't breached the limits or the I term will certainly reduce
if ( ! _motors . limit . yaw | | ( ( i > 0 & & rate_error < 0 ) | | ( i < 0 & & rate_error > 0 ) ) ) {
2015-02-11 08:10:56 -04:00
i = _pid_rate_yaw . get_i ( ) ;
2013-10-12 09:28:18 -03:00
}
2015-02-11 08:10:56 -04:00
// get d value
d = _pid_rate_yaw . get_d ( ) ;
2013-10-12 09:28:18 -03:00
// constrain output and return
return constrain_float ( ( p + i + d ) , - AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX , AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX ) ;
}
2014-06-10 03:49:49 -03:00
// accel_limiting - enable or disable accel limiting
void AC_AttitudeControl : : accel_limiting ( bool enable_limits )
{
if ( enable_limits ) {
// if enabling limits, reload from eeprom or set to defaults
2015-05-04 23:34:37 -03:00
if ( is_zero ( _accel_roll_max ) ) {
2015-02-11 08:10:56 -04:00
_accel_roll_max . load ( ) ;
}
// if enabling limits, reload from eeprom or set to defaults
2015-05-04 23:34:37 -03:00
if ( is_zero ( _accel_pitch_max ) ) {
2015-02-11 08:10:56 -04:00
_accel_pitch_max . load ( ) ;
2014-06-10 03:49:49 -03:00
}
2015-05-04 23:34:37 -03:00
if ( is_zero ( _accel_yaw_max ) ) {
2015-02-11 08:10:56 -04:00
_accel_yaw_max . load ( ) ;
2014-06-10 03:49:49 -03:00
}
} else {
// if disabling limits, set to zero
2015-02-11 08:10:56 -04:00
_accel_roll_max = 0.0f ;
_accel_pitch_max = 0.0f ;
_accel_yaw_max = 0.0f ;
2014-06-10 03:49:49 -03:00
}
}
2013-10-12 09:28:18 -03:00
//
// throttle functions
//
// set_throttle_out - to be called by upper throttle controllers when they wish to provide throttle output directly to motors
// provide 0 to cut motors
2015-06-23 10:39:26 -03:00
void AC_AttitudeControl : : set_throttle_out ( float throttle_in , bool apply_angle_boost , float filter_cutoff )
2013-10-12 09:28:18 -03:00
{
2015-06-23 10:39:26 -03:00
_throttle_in_filt . apply ( throttle_in , _dt ) ;
2015-03-25 05:18:40 -03:00
_motors . set_stabilizing ( true ) ;
2015-04-16 01:55:59 -03:00
_motors . set_throttle_filter_cutoff ( filter_cutoff ) ;
2014-01-05 23:28:35 -04:00
if ( apply_angle_boost ) {
2015-06-23 10:39:26 -03:00
_motors . set_throttle ( get_boosted_throttle ( throttle_in ) ) ;
2013-10-12 09:28:18 -03:00
} else {
2015-06-23 10:39:26 -03:00
_motors . set_throttle ( throttle_in ) ;
2013-10-12 09:28:18 -03:00
// clear angle_boost for logging purposes
2014-01-05 23:28:35 -04:00
_angle_boost = 0 ;
2013-10-12 09:28:18 -03:00
}
}
2015-03-25 05:18:40 -03:00
// outputs a throttle to all motors evenly with no attitude stabilization
2015-04-16 01:55:59 -03:00
void AC_AttitudeControl : : set_throttle_out_unstabilized ( float throttle_in , bool reset_attitude_control , float filter_cutoff )
2015-03-25 05:18:40 -03:00
{
2015-06-23 10:41:47 -03:00
_throttle_in_filt . apply ( throttle_in , _dt ) ;
2015-03-25 05:18:40 -03:00
if ( reset_attitude_control ) {
relax_bf_rate_controller ( ) ;
set_yaw_target_to_current_heading ( ) ;
}
2015-04-16 01:55:59 -03:00
_motors . set_throttle_filter_cutoff ( filter_cutoff ) ;
2015-03-25 05:18:40 -03:00
_motors . set_stabilizing ( false ) ;
_motors . set_throttle ( throttle_in ) ;
_angle_boost = 0 ;
}
2014-10-27 02:58:56 -03:00
// sqrt_controller - response based on the sqrt of the error instead of the more common linear response
float AC_AttitudeControl : : sqrt_controller ( float error , float p , float second_ord_lim )
{
2015-05-04 23:34:37 -03:00
if ( is_zero ( second_ord_lim ) | | is_zero ( p ) ) {
2014-10-27 02:58:56 -03:00
return error * p ;
}
float linear_dist = second_ord_lim / sq ( p ) ;
if ( error > linear_dist ) {
return safe_sqrt ( 2.0f * second_ord_lim * ( error - ( linear_dist / 2.0f ) ) ) ;
} else if ( error < - linear_dist ) {
return - safe_sqrt ( 2.0f * second_ord_lim * ( - error - ( linear_dist / 2.0f ) ) ) ;
} else {
return error * p ;
}
}
2015-02-11 09:03:36 -04:00
// Maximum roll rate step size that results in maximum output after 4 time steps
float AC_AttitudeControl : : max_rate_step_bf_roll ( )
{
float alpha = _pid_rate_roll . get_filt_alpha ( ) ;
float alpha_remaining = 1 - alpha ;
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ( ( alpha_remaining * alpha_remaining * alpha_remaining * alpha * _pid_rate_roll . kD ( ) ) / _dt + _pid_rate_roll . kP ( ) ) ;
}
// Maximum pitch rate step size that results in maximum output after 4 time steps
float AC_AttitudeControl : : max_rate_step_bf_pitch ( )
{
float alpha = _pid_rate_pitch . get_filt_alpha ( ) ;
float alpha_remaining = 1 - alpha ;
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ( ( alpha_remaining * alpha_remaining * alpha_remaining * alpha * _pid_rate_pitch . kD ( ) ) / _dt + _pid_rate_pitch . kP ( ) ) ;
}
// Maximum yaw rate step size that results in maximum output after 4 time steps
float AC_AttitudeControl : : max_rate_step_bf_yaw ( )
{
float alpha = _pid_rate_yaw . get_filt_alpha ( ) ;
float alpha_remaining = 1 - alpha ;
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX / ( ( alpha_remaining * alpha_remaining * alpha_remaining * alpha * _pid_rate_yaw . kD ( ) ) / _dt + _pid_rate_yaw . kP ( ) ) ;
}