2016-02-17 21:24:42 -04:00
# pragma once
2015-07-13 02:59:48 -03:00
/// @file AC_AttitudeControl_Multi.h
/// @brief ArduCopter attitude control library
2015-08-11 03:28:41 -03:00
# include "AC_AttitudeControl.h"
# include <AP_Motors/AP_MotorsMulticopter.h>
2015-07-13 02:59:48 -03:00
2016-02-15 02:25:41 -04:00
// default rate controller PID gains
# ifndef AC_ATC_MULTI_RATE_RP_P
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_RP_P 0.135f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_RP_I
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_RP_I 0.090f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_RP_D
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_RP_D 0.0036f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_RP_IMAX
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_RP_IMAX 0.444f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
# endif
# ifndef AC_ATC_MULTI_RATE_YAW_P
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_YAW_P 0.180f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_YAW_I
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_YAW_I 0.018f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_YAW_D
# define AC_ATC_MULTI_RATE_YAW_D 0.0f
# endif
# ifndef AC_ATC_MULTI_RATE_YAW_IMAX
2016-02-17 06:58:44 -04:00
# define AC_ATC_MULTI_RATE_YAW_IMAX 0.222f
2016-02-15 02:25:41 -04:00
# endif
# ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
# define AC_ATC_MULTI_RATE_YAW_FILT_HZ 5.0f
# endif
2015-07-13 02:59:48 -03:00
class AC_AttitudeControl_Multi : public AC_AttitudeControl {
public :
2016-02-15 02:25:41 -04:00
AC_AttitudeControl_Multi ( AP_AHRS & ahrs , const AP_Vehicle : : MultiCopter & aparm , AP_MotorsMulticopter & motors , float dt ) ;
2015-07-13 02:59:48 -03:00
// empty destructor to suppress compiler warning
virtual ~ AC_AttitudeControl_Multi ( ) { }
2016-02-15 02:25:41 -04:00
// pid accessors
AC_PID & get_rate_roll_pid ( ) { return _pid_rate_roll ; }
AC_PID & get_rate_pitch_pid ( ) { return _pid_rate_pitch ; }
AC_PID & get_rate_yaw_pid ( ) { return _pid_rate_yaw ; }
2016-05-23 12:12:14 -03:00
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max ( float throttle_in ) override ;
2016-03-21 07:57:39 -03:00
// Set output throttle
void set_throttle_out ( float throttle_in , bool apply_angle_boost , float filt_cutoff ) override ;
2015-07-13 02:59:48 -03:00
// calculate total body frame throttle required to produce the given earth frame throttle
2016-03-21 08:01:17 -03:00
float get_throttle_boosted ( float throttle_in ) ;
2015-07-13 02:59:48 -03:00
2016-06-09 06:39:29 -03:00
// set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
// has no effect when throttle is above hover throttle
void set_throttle_mix_min ( ) { _throttle_rpy_mix_desired = _thr_mix_min ; }
void set_throttle_mix_mid ( ) { _throttle_rpy_mix_desired = AC_ATTITUDE_CONTROL_MID_DEFAULT ; }
void set_throttle_mix_max ( ) { _throttle_rpy_mix_desired = _thr_mix_max ; }
// get_throttle_rpy_mix - get low throttle compensation value
bool is_throttle_mix_min ( ) const { return ( _throttle_rpy_mix < 1.25f * _thr_mix_min ) ; }
2016-05-23 02:03:38 -03:00
// run lowest level body-frame rate controller and send outputs to the motors
void rate_controller_run ( ) ;
2016-06-09 06:39:29 -03:00
2016-09-01 08:31:49 -03:00
// sanity check parameters. should be called once before take-off
void parameter_sanity_check ( ) ;
2016-02-15 02:25:41 -04:00
// user settable parameters
static const struct AP_Param : : GroupInfo var_info [ ] ;
2015-07-13 02:59:48 -03:00
protected :
2016-06-09 06:39:29 -03:00
// update_throttle_rpy_mix - updates thr_low_comp value towards the target
void update_throttle_rpy_mix ( ) ;
2016-06-09 05:31:59 -03:00
// get maximum value throttle can be raised to based on throttle vs attitude prioritisation
float get_throttle_avg_max ( float throttle_in ) ;
2015-07-13 02:59:48 -03:00
AP_MotorsMulticopter & _motors_multi ;
2016-02-15 02:25:41 -04:00
AC_PID _pid_rate_roll ;
AC_PID _pid_rate_pitch ;
AC_PID _pid_rate_yaw ;
2016-06-09 06:39:29 -03:00
AP_Float _thr_mix_min ; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
AP_Float _thr_mix_max ; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
2015-07-13 02:59:48 -03:00
} ;