Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h
Views: 1798
#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, const AP_MultiCopter &aparm, 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 total body frame throttle required to produce the given earth frame throttle49float get_throttle_boosted(float throttle_in);5051// set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)52// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle53// 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// are we producing min throttle?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// This function ensures that the ROV reaches the target orientation with the desired yaw rate71void input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float slew_yaw);7273// user settable parameters74static const struct AP_Param::GroupInfo var_info[];7576protected:7778// update_throttle_rpy_mix - updates thr_low_comp value towards the target79void update_throttle_rpy_mix();8081// get maximum value throttle can be raised to based on throttle vs attitude prioritisation82float get_throttle_avg_max(float throttle_in);8384AP_MotorsMulticopter& _motors_multi;8586// Roll and Pitch rate PIDs share the same defaults:87const AC_PID::Defaults rp_defaults {88AC_PID::Defaults{89.p = AC_ATC_SUB_RATE_RP_P,90.i = AC_ATC_SUB_RATE_RP_I,91.d = AC_ATC_SUB_RATE_RP_D,92.ff = 0.0f,93.imax = AC_ATC_SUB_RATE_RP_IMAX,94.filt_T_hz = AC_ATC_SUB_RATE_RP_FILT_HZ,95.filt_E_hz = 0.0,96.filt_D_hz = AC_ATC_SUB_RATE_RP_FILT_HZ,97.srmax = 0,98.srtau = 1.099}100};101AC_PID _pid_rate_roll { rp_defaults };102AC_PID _pid_rate_pitch { rp_defaults };103104AC_PID _pid_rate_yaw {105AC_PID::Defaults{106.p = AC_ATC_SUB_RATE_YAW_P,107.i = AC_ATC_SUB_RATE_YAW_I,108.d = AC_ATC_SUB_RATE_YAW_D,109.ff = 0.0f,110.imax = AC_ATC_SUB_RATE_YAW_IMAX,111.filt_T_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ,112.filt_E_hz = 0.0f,113.filt_D_hz = AC_ATC_SUB_RATE_YAW_FILT_HZ,114.srmax = 0,115.srtau = 1.0116}117};118119AP_Float _thr_mix_man; // throttle vs attitude control prioritisation used when using manual throttle (higher values mean we prioritise attitude control over throttle)120AP_Float _thr_mix_min; // throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)121AP_Float _thr_mix_max; // throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)122};123124125