APM:Libraries
AC_AttitudeControl_Multi.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include "AC_AttitudeControl.h"
8 
9 // default rate controller PID gains
10 #ifndef AC_ATC_MULTI_RATE_RP_P
11  # define AC_ATC_MULTI_RATE_RP_P 0.135f
12 #endif
13 #ifndef AC_ATC_MULTI_RATE_RP_I
14  # define AC_ATC_MULTI_RATE_RP_I 0.090f
15 #endif
16 #ifndef AC_ATC_MULTI_RATE_RP_D
17  # define AC_ATC_MULTI_RATE_RP_D 0.0036f
18 #endif
19 #ifndef AC_ATC_MULTI_RATE_RP_IMAX
20  # define AC_ATC_MULTI_RATE_RP_IMAX 0.5f
21 #endif
22 #ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
23  # define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
24 #endif
25 #ifndef AC_ATC_MULTI_RATE_YAW_P
26  # define AC_ATC_MULTI_RATE_YAW_P 0.180f
27 #endif
28 #ifndef AC_ATC_MULTI_RATE_YAW_I
29  # define AC_ATC_MULTI_RATE_YAW_I 0.018f
30 #endif
31 #ifndef AC_ATC_MULTI_RATE_YAW_D
32  # define AC_ATC_MULTI_RATE_YAW_D 0.0f
33 #endif
34 #ifndef AC_ATC_MULTI_RATE_YAW_IMAX
35  # define AC_ATC_MULTI_RATE_YAW_IMAX 0.5f
36 #endif
37 #ifndef AC_ATC_MULTI_RATE_YAW_FILT_HZ
38  # define AC_ATC_MULTI_RATE_YAW_FILT_HZ 2.5f
39 #endif
40 
41 
43 public:
45 
46  // empty destructor to suppress compiler warning
48 
49  // pid accessors
53 
54  // Update Alt_Hold angle maximum
55  void update_althold_lean_angle_max(float throttle_in) override;
56 
57  // Set output throttle
58  void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
59 
60  // calculate total body frame throttle required to produce the given earth frame throttle
61  float get_throttle_boosted(float throttle_in);
62 
63  // set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
64  // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
65  // has no effect when throttle is above hover throttle
70  float get_throttle_mix(void) const override { return _throttle_rpy_mix; }
71 
72  // are we producing min throttle?
73  bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
74 
75  // run lowest level body-frame rate controller and send outputs to the motors
76  void rate_controller_run();
77 
78  // sanity check parameters. should be called once before take-off
80 
81  // user settable parameters
82  static const struct AP_Param::GroupInfo var_info[];
83 
84 protected:
85 
86  // update_throttle_rpy_mix - updates thr_low_comp value towards the target
88 
89  // get maximum value throttle can be raised to based on throttle vs attitude prioritisation
90  float get_throttle_avg_max(float throttle_in);
91 
96 
97  AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
98  AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
99  AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
100 };
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float get_throttle_mix(void) const override
AP_MotorsMulticopter & _motors_multi
AP_MotorsMatrix motors(400)
ArduCopter attitude control library.
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
#define f(i)
void set_throttle_mix_value(float value) override
bool is_throttle_mix_min() const override
AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter &motors, float dt)
static const struct AP_Param::GroupInfo var_info[]
float value
Motor control class for Multicopters.
float get_throttle_avg_max(float throttle_in)
Copter PID control class.
Definition: AC_PID.h:17
void update_althold_lean_angle_max(float throttle_in) override
float get_throttle_boosted(float throttle_in)