APM:Libraries
AC_AttitudeControl_Sub.h
Go to the documentation of this file.
1 #pragma once
2 
5 
6 #include "AC_AttitudeControl.h"
8 
9 // default angle controller PID gains
10 // (Sub-specific defaults for parent class)
11 #define AC_ATC_SUB_ANGLE_P 6.0f
12 #define AC_ATC_SUB_ACCEL_Y_MAX 110000.0f
13 
14 // default rate controller PID gains
15 #define AC_ATC_SUB_RATE_RP_P 0.135f
16 #define AC_ATC_SUB_RATE_RP_I 0.090f
17 #define AC_ATC_SUB_RATE_RP_D 0.0036f
18 #define AC_ATC_SUB_RATE_RP_IMAX 0.444f
19 #define AC_ATC_SUB_RATE_RP_FILT_HZ 30.0f
20 #define AC_ATC_SUB_RATE_YAW_P 0.180f
21 #define AC_ATC_SUB_RATE_YAW_I 0.018f
22 #define AC_ATC_SUB_RATE_YAW_D 0.0f
23 #define AC_ATC_SUB_RATE_YAW_IMAX 0.222f
24 #define AC_ATC_SUB_RATE_YAW_FILT_HZ 5.0f
25 
27 public:
29 
30  // empty destructor to suppress compiler warning
32 
33  // pid accessors
37 
38  // Update Alt_Hold angle maximum
39  void update_althold_lean_angle_max(float throttle_in) override;
40 
41  // Set output throttle
42  void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
43 
44  // calculate total body frame throttle required to produce the given earth frame throttle
45  float get_throttle_boosted(float throttle_in);
46 
47  // set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
48  // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
49  // has no effect when throttle is above hover throttle
53 
54  // are we producing min throttle?
55  bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
56 
57  // run lowest level body-frame rate controller and send outputs to the motors
58  void rate_controller_run();
59 
60  // sanity check parameters. should be called once before take-off
62 
63  // user settable parameters
64  static const struct AP_Param::GroupInfo var_info[];
65 
66 protected:
67 
68  // update_throttle_rpy_mix - updates thr_low_comp value towards the target
70 
71  // get maximum value throttle can be raised to based on throttle vs attitude prioritisation
72  float get_throttle_avg_max(float throttle_in);
73 
78 
79  AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)
80  AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
81  AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
82 };
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override
AP_MotorsMatrix motors(400)
float get_throttle_avg_max(float throttle_in)
ArduCopter attitude control library.
static const struct AP_Param::GroupInfo var_info[]
void set_throttle_mix_man() override
void set_throttle_mix_min() override
#define f(i)
float get_throttle_boosted(float throttle_in)
AP_MotorsMulticopter & _motors_multi
void set_throttle_mix_max() override
bool is_throttle_mix_min() const override
Motor control class for Multicopters.
Copter PID control class.
Definition: AC_PID.h:17
void update_althold_lean_angle_max(float throttle_in) override
AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter &motors, float dt)