Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h
9644 views
#pragma once12/// @file AC_AttitudeControl_Sub.h3/// @brief ArduSub attitude control library45#include "AC_AttitudeControl.h"6#include <AP_Motors/AP_MotorsMulticopter.h>78// default angle controller PID gains9// (Sub-specific defaults for parent class)10#define AC_ATC_SUB_ANGLE_P 6.0f11#define AC_ATC_SUB_ACCEL_Y_MAX 110000.0f1213// default rate controller PID gains14#define AC_ATC_SUB_RATE_RP_P 0.135f15#define AC_ATC_SUB_RATE_RP_I 0.090f16#define AC_ATC_SUB_RATE_RP_D 0.0036f17#define AC_ATC_SUB_RATE_RP_IMAX 0.444f18#define AC_ATC_SUB_RATE_RP_FILT_HZ 30.0f19#define AC_ATC_SUB_RATE_YAW_P 0.180f20#define AC_ATC_SUB_RATE_YAW_I 0.018f21#define AC_ATC_SUB_RATE_YAW_D 0.0f22#define AC_ATC_SUB_RATE_YAW_IMAX 0.222f23#define AC_ATC_SUB_RATE_YAW_FILT_HZ 5.0f2425#define MAX_YAW_ERROR radians(5)2627class AC_AttitudeControl_Sub : public AC_AttitudeControl {28public:29AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, AP_MotorsMulticopter& motors);3031// empty destructor to suppress compiler warning32virtual ~AC_AttitudeControl_Sub() {}3334// pid accessors35AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }36AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }37AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }38const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; }39const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; }40const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; }4142// Update Alt_Hold angle maximum43void update_althold_lean_angle_max(float throttle_in) override;4445// Set output throttle46void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;4748// Calculate body-frame throttle required to produce the given earth-frame throttle input (accounts for vehicle tilt)49float get_throttle_boosted(float throttle_in);5051// Set desired throttle vs attitude mixing (actual mix is slewed toward this value over 1~2 seconds)52// Low values favor pilot/autopilot throttle over attitude control; high values prioritize attitude control53// Has no effect when throttle is above hover throttle54void set_throttle_mix_min() override { _throttle_rpy_mix_desired = _thr_mix_min; }55void set_throttle_mix_man() override { _throttle_rpy_mix_desired = _thr_mix_man; }56void set_throttle_mix_max(float ratio) override { _throttle_rpy_mix_desired = _thr_mix_max; }5758// Returns true if throttle mix is near minimum (i.e., attitude control is deprioritised)59bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }6061// run lowest level body-frame rate controller and send outputs to the motors62void rate_controller_run() override;6364// sanity check parameters. should be called once before take-off65void parameter_sanity_check() override;6667// set the PID notch sample rates68void set_notch_sample_rate(float sample_rate) override;6970// Sets desired roll, pitch, and yaw angles (in centidegrees), with yaw slewing.71// Slews toward target yaw at a fixed rate (in centidegrees/s) until the error is within 5 degrees.72// Used to enforce consistent heading changes without large instantaneous yaw errors.73void input_euler_angle_roll_pitch_slew_yaw_cd(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float slew_yaw_rate_cds);7475// user settable parameters76static const struct AP_Param::GroupInfo var_info[];7778protected:7980// Slews the throttle-to-attitude mix ratio (_throttle_rpy_mix) toward the requested value (_throttle_rpy_mix_desired).81// Increases rapidly and decreases more slowly to ensure stability during transitions.82void update_throttle_rpy_mix();8384// Returns a throttle value that accounts for the priority of attitude control over throttle.85// This allows graceful reduction of control authority as thrust approaches its minimum.86// returns a throttle including compensation for roll/pitch angle87// throttle value should be 0 ~ 188float get_throttle_avg_max(float throttle_in);8990AP_MotorsMulticopter& _motors_multi;9192// Roll and Pitch rate PIDs share the same defaults:93const AC_PID::Defaults rp_defaults {94AC_PID::Defaults{95.p = AC_ATC_SUB_RATE_RP_P,96.i = AC_ATC_SUB_RATE_RP_I,97.d = AC_ATC_SUB_RATE_RP_D,98.ff = 0.0f,99.imax = AC_ATC_SUB_RATE_RP_IMAX,100.filt_T_hz = AC_ATC_SUB_RATE_RP_FILT_HZ,101.filt_E_hz = 0.0,102.filt_D_hz = AC_ATC_SUB_RATE_RP_FILT_HZ,103.srmax = 0,104.srtau = 1.0105}106};107AC_PID _pid_rate_roll { rp_defaults };108AC_PID _pid_rate_pitch { rp_defaults };109110AC_PID _pid_rate_yaw {111AC_PID::Defaults{112.p = AC_ATC_SUB_RATE_YAW_P,113.i = AC_ATC_SUB_RATE_YAW_I,114.d = AC_ATC_SUB_RATE_YAW_D,115.ff = 0.0f,116.imax = AC_ATC_SUB_RATE_YAW_IMAX,117.filt_T_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ,118.filt_E_hz = 0.0f,119.filt_D_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ,120.srmax = 0,121.srtau = 1.0122}123};124125AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)126AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)127AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)128};129130131