2016-02-17 21:24:42 -04:00
# pragma once
2013-10-12 09:28:18 -03:00
/// @file AC_AttitudeControl.h
/// @brief ArduCopter attitude control library
2015-08-11 03:28:41 -03:00
# include <AP_Common/AP_Common.h>
# include <AP_Param/AP_Param.h>
# include <AP_Math/AP_Math.h>
2017-02-11 04:14:23 -04:00
# include <AP_AHRS/AP_AHRS_View.h>
2015-08-11 03:28:41 -03:00
# include <AP_Motors/AP_Motors.h>
# include <AC_PID/AC_PID.h>
# include <AC_PID/AC_P.h>
2022-09-29 20:10:39 -03:00
# include <AP_Vehicle/AP_MultiCopter.h>
2024-09-23 09:49:05 -03:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2013-10-12 09:28:18 -03:00
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_CONTROL_ANGLE_P 4.5f // default angle P gain for roll, pitch and yaw
2015-11-24 23:28:42 -04:00
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN_RADSS radians(40.0f) // minimum body-frame acceleration limit for the stability controller (for roll and pitch axis)
# define AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX_RADSS radians(720.0f) // maximum body-frame acceleration limit for the stability controller (for roll and pitch axis)
# define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS radians(10.0f) // minimum body-frame acceleration limit for the stability controller (for yaw axis)
# define AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS radians(120.0f) // maximum body-frame acceleration limit for the stability controller (for yaw axis)
2017-01-05 14:07:14 -04:00
# define AC_ATTITUDE_CONTROL_SLEW_YAW_DEFAULT_CDS 6000 // constraint on yaw angle error in degrees. This should lead to maximum turn rate of 10deg/sec * Stab Rate P so by default will be 45deg/sec.
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS 110000.0f // default maximum acceleration for roll/pitch axis in centidegrees/sec/sec
# define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS 27000.0f // default maximum acceleration for yaw axis in centidegrees/sec/sec
2014-02-14 21:07:49 -04:00
2016-02-02 08:09:26 -04:00
# define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for roll-pitch axis)
# define AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for yaw axis)
2022-01-08 07:11:11 -04:00
# define AC_ATTITUDE_RATE_RELAX_TC 0.16f // This is used to decay the rate I term to 5% in half a second.
2013-10-12 09:28:18 -03:00
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_THRUST_ERROR_ANGLE radians(30.0f) // Thrust angle error above which yaw corrections are limited
2023-09-11 20:01:11 -03:00
# define AC_ATTITUDE_YAW_MAX_ERROR_ANGLE radians(45.0f) // Thrust angle error above which yaw corrections are limited
2013-10-12 09:28:18 -03:00
2015-05-03 19:05:15 -03:00
# define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default
2014-06-06 02:04:06 -03:00
2016-05-26 10:40:35 -03:00
# define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_TC_DEFAULT 1.0f // Time constant used to limit lean angle so that vehicle does not lose altitude
# define AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX 0.8f // Max throttle used to limit lean angle so that vehicle does not lose altitude
2015-06-23 10:41:47 -03:00
2017-01-04 01:19:00 -04:00
# define AC_ATTITUDE_CONTROL_MIN_DEFAULT 0.1f // minimum throttle mix default
2019-04-11 20:53:02 -03:00
# define AC_ATTITUDE_CONTROL_MAN_DEFAULT 0.1f // manual throttle mix default
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_CONTROL_MAX_DEFAULT 0.5f // maximum throttle mix default
2021-11-23 00:51:01 -04:00
# define AC_ATTITUDE_CONTROL_MIN_LIMIT 0.5f // min throttle mix upper limit
# define AC_ATTITUDE_CONTROL_MAN_LIMIT 4.0f // man throttle mix upper limit
2017-01-04 01:19:00 -04:00
# define AC_ATTITUDE_CONTROL_MAX 5.0f // maximum throttle mix default
2016-06-09 06:39:29 -03:00
2016-06-24 04:20:21 -03:00
# define AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT 0.5f // ratio controlling the max throttle output during competing requests of low throttle from the pilot (or autopilot) and higher throttle for attitude control. Higher favours Attitude over pilot input
2022-05-11 08:37:03 -03:00
# define AC_ATTITUDE_CONTROL_THR_G_BOOST_THRESH 1.0f // default angle-p/pd throttle boost threshold
2016-06-09 06:39:29 -03:00
2013-10-12 09:28:18 -03:00
class AC_AttitudeControl {
public :
2017-02-11 04:14:23 -04:00
AC_AttitudeControl ( AP_AHRS_View & ahrs ,
2022-09-29 20:10:39 -03:00
const AP_MultiCopter & aparm ,
2022-12-05 08:21:43 -04:00
AP_Motors & motors ) :
2016-02-15 02:26:24 -04:00
_p_angle_roll ( AC_ATTITUDE_CONTROL_ANGLE_P ) ,
_p_angle_pitch ( AC_ATTITUDE_CONTROL_ANGLE_P ) ,
_p_angle_yaw ( AC_ATTITUDE_CONTROL_ANGLE_P ) ,
2015-12-08 02:48:59 -04:00
_angle_boost ( 0 ) ,
2017-12-31 19:29:28 -04:00
_use_sqrt_controller ( true ) ,
2016-06-09 06:39:29 -03:00
_throttle_rpy_mix_desired ( AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT ) ,
_throttle_rpy_mix ( AC_ATTITUDE_CONTROL_THR_MIX_DEFAULT ) ,
2015-11-24 23:28:42 -04:00
_ahrs ( ahrs ) ,
2014-01-17 22:54:23 -04:00
_aparm ( aparm ) ,
2016-02-15 02:21:38 -04:00
_motors ( motors )
2015-11-24 23:28:42 -04:00
{
2022-04-26 06:07:20 -03:00
_singleton = this ;
2015-11-24 23:28:42 -04:00
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2014-07-14 10:37:31 -03:00
2022-04-26 06:07:20 -03:00
static AC_AttitudeControl * get_singleton ( void ) {
return _singleton ;
}
2015-11-24 23:28:42 -04:00
// Empty destructor to suppress compiler warning
virtual ~ AC_AttitudeControl ( ) { }
2013-10-12 09:28:18 -03:00
2022-12-05 08:21:43 -04:00
// set_dt / get_dt - dt is the time since the last time the attitude controllers were updated
// _dt should be set based on the time of the last IMU read used by these controllers
// the attitude controller should run updates for active controllers on each loop to ensure normal operation
void set_dt ( float dt ) { _dt = dt ; }
float get_dt ( ) const { return _dt ; }
2016-02-15 02:26:24 -04:00
// pid accessors
AC_P & get_angle_roll_p ( ) { return _p_angle_roll ; }
AC_P & get_angle_pitch_p ( ) { return _p_angle_pitch ; }
AC_P & get_angle_yaw_p ( ) { return _p_angle_yaw ; }
virtual AC_PID & get_rate_roll_pid ( ) = 0 ;
virtual AC_PID & get_rate_pitch_pid ( ) = 0 ;
virtual AC_PID & get_rate_yaw_pid ( ) = 0 ;
2023-08-28 21:03:18 -03:00
virtual const AC_PID & get_rate_roll_pid ( ) const = 0 ;
virtual const AC_PID & get_rate_pitch_pid ( ) const = 0 ;
virtual const AC_PID & get_rate_yaw_pid ( ) const = 0 ;
2013-10-12 09:28:18 -03:00
2017-06-26 07:22:02 -03:00
// get the roll acceleration limit in centidegrees/s/s or radians/s/s
2021-09-06 06:45:31 -03:00
float get_accel_roll_max_cdss ( ) const { return _accel_roll_max ; }
2019-04-19 08:36:42 -03:00
float get_accel_roll_max_radss ( ) const { return radians ( _accel_roll_max * 0.01f ) ; }
2015-05-06 04:11:48 -03:00
2015-11-24 23:28:42 -04:00
// Sets the roll acceleration limit in centidegrees/s/s
2022-07-05 00:08:55 -03:00
void set_accel_roll_max_cdss ( float accel_roll_max ) { _accel_roll_max . set ( accel_roll_max ) ; }
2015-06-05 05:21:56 -03:00
2015-11-24 23:28:42 -04:00
// Sets and saves the roll acceleration limit in centidegrees/s/s
2021-09-06 06:45:31 -03:00
void save_accel_roll_max_cdss ( float accel_roll_max ) { _accel_roll_max . set_and_save ( accel_roll_max ) ; }
2015-02-11 08:10:56 -04:00
2017-06-26 07:22:02 -03:00
// get the pitch acceleration limit in centidegrees/s/s or radians/s/s
2021-09-06 06:45:31 -03:00
float get_accel_pitch_max_cdss ( ) const { return _accel_pitch_max ; }
2019-04-19 08:36:42 -03:00
float get_accel_pitch_max_radss ( ) const { return radians ( _accel_pitch_max * 0.01f ) ; }
2015-05-06 04:11:48 -03:00
2015-11-24 23:28:42 -04:00
// Sets the pitch acceleration limit in centidegrees/s/s
2022-07-05 00:08:55 -03:00
void set_accel_pitch_max_cdss ( float accel_pitch_max ) { _accel_pitch_max . set ( accel_pitch_max ) ; }
2015-06-05 05:21:56 -03:00
2015-11-24 23:28:42 -04:00
// Sets and saves the pitch acceleration limit in centidegrees/s/s
2021-09-06 06:45:31 -03:00
void save_accel_pitch_max_cdss ( float accel_pitch_max ) { _accel_pitch_max . set_and_save ( accel_pitch_max ) ; }
2015-02-11 08:10:56 -04:00
2017-06-26 07:22:02 -03:00
// get the yaw acceleration limit in centidegrees/s/s or radians/s/s
2021-09-06 06:45:31 -03:00
float get_accel_yaw_max_cdss ( ) const { return _accel_yaw_max ; }
2019-04-19 08:36:42 -03:00
float get_accel_yaw_max_radss ( ) const { return radians ( _accel_yaw_max * 0.01f ) ; }
2015-05-06 04:11:48 -03:00
2015-11-24 23:28:42 -04:00
// Sets the yaw acceleration limit in centidegrees/s/s
2022-07-05 00:08:55 -03:00
void set_accel_yaw_max_cdss ( float accel_yaw_max ) { _accel_yaw_max . set ( accel_yaw_max ) ; }
2015-06-05 05:21:56 -03:00
2015-11-24 23:28:42 -04:00
// Sets and saves the yaw acceleration limit in centidegrees/s/s
2021-09-06 06:45:31 -03:00
void save_accel_yaw_max_cdss ( float accel_yaw_max ) { _accel_yaw_max . set_and_save ( accel_yaw_max ) ; }
2015-02-11 08:10:56 -04:00
2020-01-04 02:19:00 -04:00
// get the roll angular velocity limit in radians/s
2021-10-01 09:02:30 -03:00
float get_ang_vel_roll_max_rads ( ) const { return radians ( _ang_vel_roll_max ) ; }
2024-05-19 23:37:25 -03:00
// get the roll angular velocity limit in degrees/s
float get_ang_vel_roll_max_degs ( ) const { return _ang_vel_roll_max ; }
// set the roll angular velocity limit in degrees/s
void set_ang_vel_roll_max_degs ( float vel_roll_max ) { _ang_vel_roll_max . set ( vel_roll_max ) ; }
2020-01-04 02:19:00 -04:00
// get the pitch angular velocity limit in radians/s
2021-10-01 09:02:30 -03:00
float get_ang_vel_pitch_max_rads ( ) const { return radians ( _ang_vel_pitch_max ) ; }
2024-05-19 23:37:25 -03:00
// get the pitch angular velocity limit in degrees/s
float get_ang_vel_pitch_max_degs ( ) const { return _ang_vel_pitch_max ; }
// set the pitch angular velocity limit in degrees/s
void set_ang_vel_pitch_max_degs ( float vel_pitch_max ) { _ang_vel_pitch_max . set ( vel_pitch_max ) ; }
2020-01-04 02:19:00 -04:00
2021-12-19 22:37:10 -04:00
// get the yaw angular velocity limit in radians/s
float get_ang_vel_yaw_max_rads ( ) const { return radians ( _ang_vel_yaw_max ) ; }
2024-05-19 23:37:25 -03:00
// get the yaw angular velocity limit in degrees/s
float get_ang_vel_yaw_max_degs ( ) const { return _ang_vel_yaw_max ; }
// set the yaw angular velocity limit in degrees/s
void set_ang_vel_yaw_max_degs ( float vel_yaw_max ) { _ang_vel_yaw_max . set ( vel_yaw_max ) ; }
2022-01-27 17:03:32 -04:00
// get the slew yaw rate limit in deg/s
float get_slew_yaw_max_degs ( ) const ;
2021-07-09 05:43:33 -03:00
2020-01-04 02:19:00 -04:00
// get the rate control input smoothing time constant
float get_input_tc ( ) const { return _input_tc ; }
2018-01-26 01:56:54 -04:00
// set the rate control input smoothing time constant
2022-07-05 00:08:55 -03:00
void set_input_tc ( float input_tc ) { _input_tc . set ( constrain_float ( input_tc , 0.0f , 1.0f ) ) ; }
2017-06-25 11:33:16 -03:00
2024-08-19 16:53:01 -03:00
// rate loop visible functions
2016-06-24 04:20:21 -03:00
// Ensure attitude controller have zero errors to relax rate controller output
2020-11-29 11:47:13 -04:00
void relax_attitude_controllers ( ) ;
2020-09-02 23:45:06 -03:00
2021-07-09 05:43:33 -03:00
// Used by child class AC_AttitudeControl_TS to change behaviour for tailsitter quadplanes
2020-09-02 23:45:06 -03:00
virtual void relax_attitude_controllers ( bool exclude_pitch ) { relax_attitude_controllers ( ) ; }
2014-01-11 04:02:42 -04:00
2016-07-11 23:24:27 -03:00
// reset rate controller I terms
void reset_rate_controller_I_terms ( ) ;
2020-11-17 23:38:18 -04:00
// reset rate controller I terms smoothly to zero in 0.5 seconds
void reset_rate_controller_I_terms_smoothly ( ) ;
2024-07-23 04:31:53 -03:00
// Reduce attitude control gains while landed to stop ground resonance
void landed_gain_reduction ( bool landed ) ;
2021-05-24 20:38:16 -03:00
// Sets attitude target to vehicle attitude and sets all rates to zero
2021-07-09 09:11:33 -03:00
// If reset_rate is false rates are not reset to allow the rate controllers to run
void reset_target_and_rate ( bool reset_rate = true ) ;
2017-04-15 21:34:13 -03:00
2021-05-24 10:31:40 -03:00
// Sets yaw target to vehicle heading and sets yaw rate to zero
2021-07-09 09:11:33 -03:00
// If reset_rate is false rates are not reset to allow the rate controllers to run
void reset_yaw_target_and_rate ( bool reset_rate = true ) ;
2015-06-23 04:49:12 -03:00
2017-12-31 19:53:29 -04:00
// handle reset of attitude from EKF since the last iteration
void inertial_frame_reset ( ) ;
2024-08-19 16:53:01 -03:00
// Command euler yaw rate and pitch angle with roll angle specified in body frame
// (implemented only in AC_AttitudeControl_TS for tailsitter quadplanes)
virtual void input_euler_rate_yaw_euler_angle_pitch_bf_roll ( bool plane_controls , float euler_roll_angle_cd ,
float euler_pitch_angle_cd , float euler_yaw_rate_cds ) { }
////// begin rate update functions //////
// These functions all update _ang_vel_body which is used as the rate target by the rate controller.
// Since _ang_vel_body can be seen by the rate controller thread all these functions only set it
// at the end once all of the calculations have been performed. This avoids intermediate results being
// used by the rate controller when running concurrently. _ang_vel_body is accessed so commonly that
// locking proves to be moderately expensive, however since this is changing incrementally values combining
// previous and current elements are safe and do not have an impact on control.
// Any additional functions that are added to manipulate _ang_vel_body should follow this pattern.
// Calculates the body frame angular velocities to follow the target attitude
// This is used by most of the subsequent functions
void attitude_controller_run_quat ( ) ;
2016-06-24 04:20:21 -03:00
// Command a Quaternion attitude with feedforward and smoothing
2023-08-09 22:57:00 -03:00
// attitude_desired_quat: is updated on each time_step (_dt) by the integral of the body frame angular velocity
virtual void input_quaternion ( Quaternion & attitude_desired_quat , Vector3f ang_vel_body ) ;
2014-02-19 02:55:45 -04:00
2016-06-24 04:20:21 -03:00
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
virtual void input_euler_angle_roll_pitch_euler_rate_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_rate_cds ) ;
2016-06-24 04:20:21 -03:00
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
2017-06-25 11:33:16 -03:00
virtual void input_euler_angle_roll_pitch_yaw ( float euler_roll_angle_cd , float euler_pitch_angle_cd , float euler_yaw_angle_cd , bool slew_yaw ) ;
2014-01-11 04:02:42 -04:00
2016-06-24 04:20:21 -03:00
// Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
2021-01-26 08:54:13 -04:00
virtual void input_euler_rate_roll_pitch_yaw ( float euler_roll_rate_cds , float euler_pitch_rate_cds , float euler_yaw_rate_cds ) ;
2014-01-28 04:30:33 -04:00
2024-08-19 16:53:01 -03:00
// Fully stabilized acro
2016-06-24 04:20:21 -03:00
// Command an angular velocity with angular velocity feedforward and smoothing
2015-11-28 13:56:25 -04:00
virtual void input_rate_bf_roll_pitch_yaw ( float roll_rate_bf_cds , float pitch_rate_bf_cds , float yaw_rate_bf_cds ) ;
2014-01-24 22:59:48 -04:00
2024-08-19 16:53:01 -03:00
// Rate-only acro with no attitude feedback - used only by Copter rate-only acro
// Command an angular velocity with angular velocity smoothing using rate loops only with no attitude loop stabilization
2021-01-26 08:54:13 -04:00
virtual void input_rate_bf_roll_pitch_yaw_2 ( float roll_rate_bf_cds , float pitch_rate_bf_cds , float yaw_rate_bf_cds ) ;
2017-12-31 19:53:29 -04:00
2024-08-19 16:53:01 -03:00
// Acro with attitude feedback that does not rely on attitude - used only by Plane acro
2017-12-31 19:53:29 -04:00
// Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
2021-01-26 08:54:13 -04:00
virtual void input_rate_bf_roll_pitch_yaw_3 ( float roll_rate_bf_cds , float pitch_rate_bf_cds , float yaw_rate_bf_cds ) ;
2017-12-31 19:53:29 -04:00
2017-06-15 10:10:01 -03:00
// Command an angular step (i.e change) in body frame angle
virtual void input_angle_step_bf_roll_pitch_yaw ( float roll_angle_step_bf_cd , float pitch_angle_step_bf_cd , float yaw_angle_step_bf_cd ) ;
2024-05-16 11:10:47 -03:00
// Command an angular rate step (i.e change) in body frame rate
virtual void input_rate_step_bf_roll_pitch_yaw ( float roll_rate_step_bf_cd , float pitch_rate_step_bf_cd , float yaw_rate_step_bf_cd ) ;
2021-04-15 09:24:43 -03:00
// Command a thrust vector in the earth frame and a heading angle and/or rate
2022-05-14 00:55:34 -03:00
virtual void input_thrust_vector_rate_heading ( const Vector3f & thrust_vector , float heading_rate_cds , bool slew_yaw = true ) ;
2024-08-19 16:53:01 -03:00
2021-06-20 13:56:43 -03:00
virtual void input_thrust_vector_heading ( const Vector3f & thrust_vector , float heading_angle_cd , float heading_rate_cds ) ;
2021-04-15 09:24:43 -03:00
void input_thrust_vector_heading ( const Vector3f & thrust_vector , float heading_cd ) { input_thrust_vector_heading ( thrust_vector , heading_cd , 0.0f ) ; }
2024-08-19 16:53:01 -03:00
////// end rate update functions //////
2021-04-15 09:24:43 -03:00
// Converts thrust vector and heading angle to quaternion rotation in the earth frame
Quaternion attitude_from_thrust_vector ( Vector3f thrust_vector , float heading_angle ) const ;
2015-11-24 23:28:42 -04:00
// Run angular velocity controller and send outputs to the motors
2016-05-23 02:03:38 -03:00
virtual void rate_controller_run ( ) = 0 ;
2013-10-12 09:28:18 -03:00
2024-08-01 18:10:34 -03:00
// reset target loop rate modifications
virtual void rate_controller_target_reset ( ) { }
2024-05-13 08:25:50 -03:00
// optional variant to allow running with different dt
2024-09-24 06:27:56 -03:00
virtual void rate_controller_run_dt ( const Vector3f & gyro , float dt ) { AP_BoardConfig : : config_error ( " rate_controller_run_dt() must be defined " ) ; } ;
2024-05-13 08:25:50 -03:00
2015-11-24 23:28:42 -04:00
// Convert a 321-intrinsic euler angle derivative to an angular velocity vector
2024-02-19 19:46:36 -04:00
void euler_rate_to_ang_vel ( const Quaternion & att , const Vector3f & euler_rate_rads , Vector3f & ang_vel_rads ) ;
2013-10-12 09:28:18 -03:00
2015-11-24 23:28:42 -04:00
// Convert an angular velocity vector to a 321-intrinsic euler angle derivative
// Returns false if the vehicle is pitched 90 degrees up or down
2024-02-19 19:46:36 -04:00
bool ang_vel_to_euler_rate ( const Quaternion & att , const Vector3f & ang_vel_rads , Vector3f & euler_rate_rads ) ;
2013-10-12 09:28:18 -03:00
2017-12-31 19:29:28 -04:00
// Specifies whether the attitude controller should use the square root controller in the attitude correction.
// This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller.
void use_sqrt_controller ( bool use_sqrt_cont ) { _use_sqrt_controller = use_sqrt_cont ; }
2013-10-12 09:28:18 -03:00
2015-11-24 23:28:42 -04:00
// Return 321-intrinsic euler angles in centidegrees representing the rotation from NED earth frame to the
2016-06-24 04:20:21 -03:00
// attitude controller's target attitude.
2016-09-27 21:04:53 -03:00
// **NOTE** Using vector3f*deg(100) is more efficient than deg(vector3f)*100 or deg(vector3d*100) because it gives the
2017-01-05 14:07:14 -04:00
// same result with the fewest multiplications. Even though it may look like a bug, it is intentional. See issue 4895.
2021-04-14 12:42:42 -03:00
Vector3f get_att_target_euler_cd ( ) const { return _euler_angle_target * degrees ( 100.0f ) ; }
const Vector3f & get_att_target_euler_rad ( ) const { return _euler_angle_target ; }
2013-10-12 09:28:18 -03:00
2019-03-29 14:24:19 -03:00
// Return the body-to-NED target attitude used by the quadplane-specific attitude control input methods
2021-04-14 12:42:42 -03:00
Quaternion get_attitude_target_quat ( ) const { return _attitude_target ; }
2019-03-29 14:24:19 -03:00
2022-02-03 03:53:29 -04:00
// Return the angular velocity of the target (setpoint) [rad/s] in the target attitude frame
const Vector3f & get_attitude_target_ang_vel ( ) const { return _ang_vel_target ; }
2016-06-24 04:20:21 -03:00
// Return the angle between the target thrust vector and the current thrust vector.
float get_att_error_angle_deg ( ) const { return degrees ( _thrust_error_angle ) ; }
2013-10-12 09:28:18 -03:00
2016-06-24 04:20:21 -03:00
// Set z-axis angular velocity in centidegrees/s
2021-04-14 12:42:42 -03:00
void rate_bf_yaw_target ( float rate_cds ) { _ang_vel_body . z = radians ( rate_cds * 0.01f ) ; }
2015-11-24 23:28:42 -04:00
2019-07-29 04:56:03 -03:00
// Set x-axis system identification angular velocity in degrees/s
2021-04-14 12:42:42 -03:00
void rate_bf_roll_sysid ( float rate ) { _sysid_ang_vel_body . x = rate ; }
2019-07-29 04:56:03 -03:00
// Set y-axis system identification angular velocity in degrees/s
2021-04-14 12:42:42 -03:00
void rate_bf_pitch_sysid ( float rate ) { _sysid_ang_vel_body . y = rate ; }
2019-07-29 04:56:03 -03:00
// Set z-axis system identification angular velocity in degrees/s
2021-04-14 12:42:42 -03:00
void rate_bf_yaw_sysid ( float rate ) { _sysid_ang_vel_body . z = rate ; }
2019-07-29 04:56:03 -03:00
// Set x-axis system identification actuator
void actuator_roll_sysid ( float command ) { _actuator_sysid . x = command ; }
// Set y-axis system identification actuator
void actuator_pitch_sysid ( float command ) { _actuator_sysid . y = command ; }
// Set z-axis system identification actuator
void actuator_yaw_sysid ( float command ) { _actuator_sysid . z = command ; }
2016-08-05 23:54:19 -03:00
// Return roll rate step size in radians/s that results in maximum output after 4 time steps
2015-02-11 09:03:36 -04:00
float max_rate_step_bf_roll ( ) ;
2015-11-24 23:28:42 -04:00
2016-08-05 23:54:19 -03:00
// Return pitch rate step size in radians/s that results in maximum output after 4 time steps
2015-02-11 09:03:36 -04:00
float max_rate_step_bf_pitch ( ) ;
2015-11-24 23:28:42 -04:00
2016-08-05 23:54:19 -03:00
// Return yaw rate step size in radians/s that results in maximum output after 4 time steps
2015-02-11 09:03:36 -04:00
float max_rate_step_bf_yaw ( ) ;
2016-08-05 23:54:19 -03:00
// Return roll step size in radians that results in maximum output after 4 time steps
2019-04-19 08:36:42 -03:00
float max_angle_step_bf_roll ( ) { return max_rate_step_bf_roll ( ) / _p_angle_roll . kP ( ) ; }
2015-11-24 23:28:42 -04:00
2016-08-05 23:54:19 -03:00
// Return pitch step size in radians that results in maximum output after 4 time steps
2019-04-19 08:36:42 -03:00
float max_angle_step_bf_pitch ( ) { return max_rate_step_bf_pitch ( ) / _p_angle_pitch . kP ( ) ; }
2015-11-24 23:28:42 -04:00
2016-08-05 23:54:19 -03:00
// Return yaw step size in radians that results in maximum output after 4 time steps
2019-04-19 08:36:42 -03:00
float max_angle_step_bf_yaw ( ) { return max_rate_step_bf_yaw ( ) / _p_angle_yaw . kP ( ) ; }
2015-02-11 09:03:36 -04:00
2016-06-24 04:20:21 -03:00
// Return angular velocity in radians used in the angular velocity controller
2021-04-14 12:42:42 -03:00
Vector3f rate_bf_targets ( ) const { return _ang_vel_body + _sysid_ang_vel_body ; }
2015-02-11 09:01:11 -04:00
2023-01-06 03:56:49 -04:00
// return the angular velocity of the target (setpoint) attitude rad/s
const Vector3f & get_rate_ef_targets ( ) const { return _euler_rate_target ; }
2015-11-24 23:28:42 -04:00
// Enable or disable body-frame feed forward
2022-07-05 00:08:55 -03:00
void bf_feedforward ( bool enable_or_disable ) { _rate_bf_ff_enabled . set ( enable_or_disable ) ; }
2014-06-10 03:49:49 -03:00
2015-11-24 23:28:42 -04:00
// Enable or disable body-frame feed forward and save
2015-05-08 02:28:41 -03:00
void bf_feedforward_save ( bool enable_or_disable ) { _rate_bf_ff_enabled . set_and_save ( enable_or_disable ) ; }
2015-05-06 04:11:48 -03:00
2015-11-24 23:28:42 -04:00
// Return body-frame feed forward setting
2015-02-11 07:07:29 -04:00
bool get_bf_feedforward ( ) { return _rate_bf_ff_enabled ; }
2015-11-24 23:28:42 -04:00
// Enable or disable body-frame feed forward
2014-06-10 03:49:49 -03:00
void accel_limiting ( bool enable_or_disable ) ;
2016-05-23 12:12:14 -03:00
// Update Alt_Hold angle maximum
virtual void update_althold_lean_angle_max ( float throttle_in ) = 0 ;
2015-11-24 23:28:42 -04:00
// Set output throttle
2016-03-21 07:57:39 -03:00
virtual void set_throttle_out ( float throttle_in , bool apply_angle_boost , float filt_cutoff ) = 0 ;
2015-03-25 05:18:40 -03:00
2016-01-04 04:14:01 -04:00
// get throttle passed into attitude controller (i.e. throttle_in provided to set_throttle_out)
float get_throttle_in ( ) const { return _throttle_in ; }
2015-11-24 23:28:42 -04:00
// Return throttle increase applied for tilt compensation
2016-01-03 23:44:45 -04:00
float angle_boost ( ) const { return _angle_boost ; }
2015-06-23 10:41:47 -03:00
2015-11-24 23:28:42 -04:00
// Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
2021-09-06 06:45:31 -03:00
virtual float get_althold_lean_angle_max_cd ( ) const ;
2013-10-12 09:28:18 -03:00
2016-04-28 04:46:58 -03:00
// Return configured tilt angle limit in centidegrees
2021-09-06 06:45:31 -03:00
float lean_angle_max_cd ( ) const { return _aparm . angle_max ; }
2014-01-17 22:54:23 -04:00
2019-07-29 04:56:03 -03:00
// Return tilt angle in degrees
2021-09-06 06:45:31 -03:00
float lean_angle_deg ( ) const { return degrees ( _thrust_angle ) ; }
2019-07-29 04:56:03 -03:00
2016-06-24 04:20:21 -03:00
// calculates the velocity correction from an angle error. The angular velocity has acceleration and
// deceleration limits including basic jerk limiting using smoothing_gain
2021-04-15 09:24:43 -03:00
static float input_shaping_angle ( float error_angle , float input_tc , float accel_max , float target_ang_vel , float desired_ang_vel , float max_ang_vel , float dt ) ;
2022-01-11 17:47:09 -04:00
static float input_shaping_angle ( float error_angle , float input_tc , float accel_max , float target_ang_vel , float dt ) { return input_shaping_angle ( error_angle , input_tc , accel_max , target_ang_vel , 0.0f , 0.0f , dt ) ; }
2015-12-02 19:47:52 -04:00
2022-06-24 00:11:32 -03:00
// Shapes the velocity request based on a rate time constant. The angular acceleration and deceleration is limited.
static float input_shaping_ang_vel ( float target_ang_vel , float desired_ang_vel , float accel_max , float dt , float input_tc ) ;
2022-03-14 14:04:37 -03:00
2017-11-10 11:22:57 -04:00
// calculates the expected angular velocity correction from an angle error based on the AC_AttitudeControl settings.
// This function can be used to predict the delay associated with angle requests.
2018-12-20 05:10:02 -04:00
void input_shaping_rate_predictor ( const Vector2f & error_angle , Vector2f & target_ang_vel , float dt ) const ;
2017-11-10 11:22:57 -04:00
2017-11-15 09:45:34 -04:00
// translates body frame acceleration limits to the euler axis
void ang_vel_limit ( Vector3f & euler_rad , float ang_vel_roll_max , float ang_vel_pitch_max , float ang_vel_yaw_max ) const ;
2015-12-02 19:47:52 -04:00
2016-06-24 04:20:21 -03:00
// translates body frame acceleration limits to the euler axis
2024-02-19 19:46:36 -04:00
Vector3f euler_accel_limit ( const Quaternion & att , const Vector3f & euler_accel ) ;
2015-12-02 19:47:52 -04:00
2024-09-10 08:11:51 -03:00
// Calculates the body frame angular velocities to follow the target attitude
void update_attitude_target ( ) ;
2021-04-14 12:42:42 -03:00
// thrust_heading_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
2021-04-14 12:20:26 -03:00
// The maximum error in the yaw axis is limited based on the angle yaw P value and acceleration.
2021-04-15 09:24:43 -03:00
void thrust_heading_rotation_angles ( Quaternion & attitude_target , const Quaternion & attitude_body , Vector3f & attitude_error , float & thrust_angle , float & thrust_error_angle ) const ;
2021-04-14 12:20:26 -03:00
2021-04-14 12:42:42 -03:00
// thrust_vector_rotation_angles - calculates two ordered rotations to move the attitude_body quaternion to the attitude_target quaternion.
2021-04-14 12:20:26 -03:00
// The first rotation corrects the thrust vector and the second rotation corrects the heading vector.
2021-04-15 09:24:43 -03:00
void thrust_vector_rotation_angles ( const Quaternion & attitude_target , const Quaternion & attitude_body , Quaternion & thrust_vector_correction , Vector3f & attitude_error , float & thrust_angle , float & thrust_error_angle ) const ;
2021-04-14 12:20:26 -03:00
2016-09-01 08:31:49 -03:00
// sanity check parameters. should be called once before take-off
virtual void parameter_sanity_check ( ) { }
2023-07-27 10:59:16 -03:00
// set the PID notch sample rates
virtual void set_notch_sample_rate ( float sample_rate ) { }
2017-01-09 03:30:34 -04:00
// return true if the rpy mix is at lowest value
virtual bool is_throttle_mix_min ( ) const { return true ; }
// control rpy throttle mix
virtual void set_throttle_mix_min ( ) { }
2017-01-04 01:19:00 -04:00
virtual void set_throttle_mix_man ( ) { }
2019-06-17 12:36:22 -03:00
virtual void set_throttle_mix_max ( float ratio ) { }
2017-01-28 19:40:34 -04:00
virtual void set_throttle_mix_value ( float value ) { }
2017-04-18 09:24:48 -03:00
virtual float get_throttle_mix ( void ) const { return 0 ; }
2017-01-09 03:30:34 -04:00
// enable use of flybass passthrough on heli
virtual void use_flybar_passthrough ( bool passthrough , bool tail_passthrough ) { }
// use_leaky_i - controls whether we use leaky i term for body-frame to motor output stage on heli
virtual void use_leaky_i ( bool leaky_i ) { }
// set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition.
virtual void set_hover_roll_trim_scalar ( float scalar ) { }
2020-11-17 23:38:18 -04:00
// Return angle in centidegrees to be added to roll angle for hover collective learn. Used by heli to counteract
// tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle.
virtual float get_roll_trim_cd ( ) { return 0 ; }
2017-01-09 03:30:34 -04:00
// passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
virtual void passthrough_bf_roll_pitch_rate_yaw ( float roll_passthrough , float pitch_passthrough , float yaw_rate_bf_cds ) { } ;
2017-08-27 20:48:36 -03:00
2019-03-04 23:27:31 -04:00
// provide feedback on whether arming would be a good idea right now:
bool pre_arm_checks ( const char * param_prefix ,
char * failure_msg ,
const uint8_t failure_msg_len ) ;
2017-08-27 20:48:36 -03:00
// enable inverted flight on backends that support it
virtual void set_inverted_flight ( bool inverted ) { }
2022-04-26 06:07:20 -03:00
2024-03-07 23:24:43 -04:00
// enable accessor for inverted flight flag on backends that support it
virtual bool get_inverted_flight ( ) { return false ; }
2022-04-30 06:25:33 -03:00
// get the slew rate value for roll, pitch and yaw, for oscillation detection in lua scripts
void get_rpy_srate ( float & roll_srate , float & pitch_srate , float & yaw_srate ) ;
2022-03-14 14:04:37 -03:00
// Sets the roll and pitch rate shaping time constant
void set_roll_pitch_rate_tc ( float input_tc ) { _rate_rp_tc = input_tc ; }
// Sets the yaw rate shaping time constant
void set_yaw_rate_tc ( float input_tc ) { _rate_y_tc = input_tc ; }
2022-10-10 19:14:35 -03:00
// setup a one loop angle P scale multiplier. This replaces any previous scale applied
// so should only be used when only one source of scaling is needed
void set_angle_P_scale ( const Vector3f & angle_P_scale ) { _angle_P_scale = angle_P_scale ; }
// setup a one loop angle P scale multiplier, multiplying by any
// previously applied scale from this loop. This allows for more
// than one type of scale factor to be applied for different
// purposes
void set_angle_P_scale_mult ( const Vector3f & angle_P_scale ) { _angle_P_scale * = angle_P_scale ; }
2023-08-09 10:33:55 -03:00
// get the value of the angle P scale that was used in the last loop
const Vector3f & get_last_angle_P_scale ( void ) const { return _angle_P_scale_used ; }
2022-10-10 19:14:35 -03:00
2022-05-11 08:37:03 -03:00
// setup a one loop PD scale multiplier, multiplying by any
// previously applied scale from this loop. This allows for more
// than one type of scale factor to be applied for different
// purposes
void set_PD_scale_mult ( const Vector3f & pd_scale ) { _pd_scale * = pd_scale ; }
2024-08-22 16:14:14 -03:00
// write RATE message
void Write_Rate ( const AC_PosControl & pos_control ) const ;
2022-05-11 08:37:03 -03:00
2024-09-10 07:52:38 -03:00
// write ANG message
void Write_ANG ( ) const ;
2016-09-01 08:30:21 -03:00
// User settable parameters
static const struct AP_Param : : GroupInfo var_info [ ] ;
2016-01-20 14:41:32 -04:00
2022-05-11 08:37:03 -03:00
static constexpr Vector3f VECTORF_111 { 1.0f , 1.0f , 1.0f } ;
2016-06-24 04:20:21 -03:00
protected :
2014-02-09 22:59:51 -04:00
2016-06-24 04:20:21 -03:00
// Update rate_target_ang_vel using attitude_error_rot_vec_rad
2018-12-20 05:10:02 -04:00
Vector3f update_ang_vel_target_from_att_error ( const Vector3f & attitude_error_rot_vec_rad ) ;
2014-02-09 22:59:51 -04:00
2015-11-24 23:28:42 -04:00
// Return angle in radians to be added to roll angle. Used by heli to counteract
// tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle.
2015-11-27 19:31:16 -04:00
virtual float get_roll_trim_rad ( ) { return 0 ; }
2015-11-24 17:11:50 -04:00
2015-11-24 23:28:42 -04:00
// Return the yaw slew rate limit in radians/s
2022-01-27 17:03:32 -04:00
float get_slew_yaw_max_rads ( ) const { return radians ( get_slew_yaw_max_degs ( ) ) ; }
2015-11-24 23:28:42 -04:00
2024-09-21 08:22:13 -03:00
// get the latest gyro for the purposes of attitude control
const Vector3f get_latest_gyro ( ) const ;
2015-11-24 23:28:42 -04:00
// Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
AP_Float _slew_yaw ;
2017-11-15 09:45:34 -04:00
// Maximum angular velocity (in degrees/second) for earth-frame roll, pitch and yaw axis
AP_Float _ang_vel_roll_max ;
AP_Float _ang_vel_pitch_max ;
AP_Float _ang_vel_yaw_max ;
2015-11-24 23:28:42 -04:00
// Maximum rotation acceleration for earth-frame roll axis
AP_Float _accel_roll_max ;
// Maximum rotation acceleration for earth-frame pitch axis
AP_Float _accel_pitch_max ;
// Maximum rotation acceleration for earth-frame yaw axis
AP_Float _accel_yaw_max ;
// Enable/Disable body frame rate feed forward
AP_Int8 _rate_bf_ff_enabled ;
2016-01-06 23:11:27 -04:00
// Enable/Disable angle boost
AP_Int8 _angle_boost_enabled ;
2016-02-15 02:26:24 -04:00
// angle controller P objects
AC_P _p_angle_roll ;
AC_P _p_angle_pitch ;
AC_P _p_angle_yaw ;
2016-05-26 10:40:35 -03:00
// Angle limit time constant (to maintain altitude)
AP_Float _angle_limit_tc ;
2018-01-26 01:56:54 -04:00
// rate controller input smoothing time constant
AP_Float _input_tc ;
2024-07-23 04:31:53 -03:00
// Controller gain multiplyer to be used when landed
AP_Float _land_roll_mult ;
AP_Float _land_pitch_mult ;
AP_Float _land_yaw_mult ;
2024-08-22 16:14:14 -03:00
// latest gyro value use by the rate_controller
Vector3f _rate_gyro ;
// timestamp of the latest gyro value used by the rate controller
uint64_t _rate_gyro_time_us ;
2015-11-24 23:28:42 -04:00
// Intersampling period in seconds
float _dt ;
2018-01-19 02:26:41 -04:00
// This represents a 321-intrinsic rotation in NED frame to the target (setpoint)
2016-06-24 04:20:21 -03:00
// attitude used in the attitude controller, in radians.
2021-04-20 21:26:54 -03:00
Vector3f _euler_angle_target ;
2015-11-24 23:28:42 -04:00
2016-06-24 04:20:21 -03:00
// This represents the angular velocity of the target (setpoint) attitude used in
2015-12-02 18:05:13 -04:00
// the attitude controller as 321-intrinsic euler angle derivatives, in radians per
2016-06-24 04:20:21 -03:00
// second.
2021-04-14 12:42:42 -03:00
Vector3f _euler_rate_target ;
2016-06-24 04:20:21 -03:00
2018-01-19 02:26:41 -04:00
// This represents a quaternion rotation in NED frame to the target (setpoint)
2016-06-24 04:20:21 -03:00
// attitude used in the attitude controller.
2021-04-14 12:42:42 -03:00
Quaternion _attitude_target ;
2015-11-24 23:28:42 -04:00
2016-06-24 04:20:21 -03:00
// This represents the angular velocity of the target (setpoint) attitude used in
2015-12-02 18:05:13 -04:00
// the attitude controller as an angular velocity vector, in radians per second in
2016-06-24 04:20:21 -03:00
// the target attitude frame.
2021-04-14 12:42:42 -03:00
Vector3f _ang_vel_target ;
2015-11-24 23:28:42 -04:00
2018-01-19 02:26:41 -04:00
// This represents the angular velocity in radians per second in the body frame, used in the angular
2024-08-19 16:53:01 -03:00
// velocity controller and most importantly the rate controller.
2021-04-14 12:42:42 -03:00
Vector3f _ang_vel_body ;
2016-06-24 04:20:21 -03:00
2022-05-23 01:50:27 -03:00
// This is the angular velocity in radians per second in the body frame, added to the output angular
2019-07-29 04:56:03 -03:00
// attitude controller by the System Identification Mode.
// It is reset to zero immediately after it is used.
2021-04-14 12:42:42 -03:00
Vector3f _sysid_ang_vel_body ;
2019-07-29 04:56:03 -03:00
2022-05-23 01:50:27 -03:00
// This is the unitless value added to the output of the PID by the System Identification Mode.
2019-07-29 04:56:03 -03:00
// It is reset to zero immediately after it is used.
Vector3f _actuator_sysid ;
2017-12-31 19:53:29 -04:00
// This represents a quaternion attitude error in the body frame, used for inertial frame reset handling.
Quaternion _attitude_ang_error ;
2019-07-29 04:56:03 -03:00
// The angle between the target thrust vector and the current thrust vector.
float _thrust_angle ;
2016-06-24 04:20:21 -03:00
// The angle between the target thrust vector and the current thrust vector.
float _thrust_error_angle ;
2015-11-24 23:28:42 -04:00
2016-01-04 04:14:01 -04:00
// throttle provided as input to attitude controller. This does not include angle boost.
float _throttle_in = 0.0f ;
2015-11-24 23:28:42 -04:00
// This represents the throttle increase applied for tilt compensation.
// Used only for logging.
2016-01-03 23:44:45 -04:00
float _angle_boost ;
2015-11-24 23:28:42 -04:00
2017-12-31 19:29:28 -04:00
// Specifies whether the attitude controller should use the square root controller in the attitude correction.
// This is used during Autotune to ensure the P term is tuned without being influenced by the acceleration limit of the square root controller.
bool _use_sqrt_controller ;
2015-11-24 23:28:42 -04:00
2016-05-23 12:12:14 -03:00
// Filtered Alt_Hold lean angle max - used to limit lean angle when throttle is saturated using Alt_Hold
2016-05-26 10:11:58 -03:00
float _althold_lean_angle_max = 0.0f ;
2015-11-24 23:28:42 -04:00
2016-06-24 04:20:21 -03:00
// desired throttle_low_comp value, actual throttle_low_comp is slewed towards this value over 1~2 seconds
float _throttle_rpy_mix_desired ;
// mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1
float _throttle_rpy_mix ;
2016-06-09 06:39:29 -03:00
2019-07-09 09:42:16 -03:00
// Yaw feed forward percent to allow zero yaw actuator output during extreme roll and pitch corrections
float _feedforward_scalar = 1.0f ;
2022-03-14 14:04:37 -03:00
// rate controller input smoothing time constant
float _rate_rp_tc ;
float _rate_y_tc ;
2022-10-10 19:14:35 -03:00
// angle P scaling vector for roll, pitch, yaw
Vector3f _angle_P_scale { 1 , 1 , 1 } ;
2023-08-09 10:33:55 -03:00
// angle scale used for last loop, used for logging and quadplane angle P scaling
2022-10-10 19:14:35 -03:00
Vector3f _angle_P_scale_used ;
2022-05-11 08:37:03 -03:00
// PD scaling vector for roll, pitch, yaw
Vector3f _pd_scale { 1 , 1 , 1 } ;
// PD scale used for last loop, used for logging
Vector3f _pd_scale_used ;
2024-07-23 04:31:53 -03:00
// ratio of normal gain to landed gain
float _landed_gain_ratio ;
2015-11-24 23:28:42 -04:00
// References to external libraries
2017-02-11 04:14:23 -04:00
const AP_AHRS_View & _ahrs ;
2022-09-29 20:10:39 -03:00
const AP_MultiCopter & _aparm ;
2013-10-12 09:28:18 -03:00
AP_Motors & _motors ;
2016-05-27 01:13:02 -03:00
2022-04-26 06:07:20 -03:00
static AC_AttitudeControl * _singleton ;
2016-05-31 04:07:33 -03:00
protected :
2016-05-27 01:13:02 -03:00
/*
state of control monitoring
*/
struct {
2016-06-09 03:00:57 -03:00
float rms_roll_P ;
float rms_roll_D ;
float rms_pitch_P ;
float rms_pitch_D ;
2016-05-27 01:13:02 -03:00
float rms_yaw ;
} _control_monitor ;
// update state in ControlMonitor
2016-06-09 03:00:57 -03:00
void control_monitor_filter_pid ( float value , float & rms_P ) ;
2016-05-27 01:13:02 -03:00
void control_monitor_update ( void ) ;
public :
// log a CTRL message
2021-02-01 12:26:25 -04:00
void control_monitor_log ( void ) const ;
2016-05-27 01:13:02 -03:00
2016-06-01 04:18:58 -03:00
// return current RMS controller filter for each axis
float control_monitor_rms_output_roll ( void ) const ;
2016-06-09 03:25:19 -03:00
float control_monitor_rms_output_roll_P ( void ) const ;
float control_monitor_rms_output_roll_D ( void ) const ;
float control_monitor_rms_output_pitch_P ( void ) const ;
float control_monitor_rms_output_pitch_D ( void ) const ;
2016-06-01 04:18:58 -03:00
float control_monitor_rms_output_pitch ( void ) const ;
float control_monitor_rms_output_yaw ( void ) const ;
2022-09-06 05:47:56 -03:00
// structure for angle and/or rate target
enum class HeadingMode {
Angle_Only ,
Angle_And_Rate ,
Rate_Only
} ;
struct HeadingCommand {
float yaw_angle_cd ;
float yaw_rate_cds ;
HeadingMode heading_mode ;
} ;
void input_thrust_vector_heading ( const Vector3f & thrust_vector , HeadingCommand heading ) ;
2013-10-12 09:28:18 -03:00
} ;