ardupilot/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h

96 lines
3.7 KiB
C
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#pragma once
/// @file AC_AttitudeControl_Multi.h
/// @brief ArduCopter attitude control library
#include "AC_AttitudeControl.h"
#include <AP_Motors/AP_MotorsMulticopter.h>
2016-02-15 02:25:41 -04:00
// default rate controller PID gains
#ifndef AC_ATC_MULTI_RATE_RP_P
# 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
# 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
# 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
# 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
# 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
# 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
# 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
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);
// 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; }
// get lean angle max for pilot input that prioritizes altitude hold over lean angle
float get_althold_lean_angle_max() const;
// Set output throttle
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override;
// calculate total body frame throttle required to produce the given earth frame throttle
float get_throttle_boosted(float throttle_in);
// calculate total body frame throttle required to produce the given earth frame throttle
float get_throttle_ave_max(float throttle_in);
// 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); }
// run lowest level body-frame rate controller and send outputs to the motors
void rate_controller_run();
2016-02-15 02:25:41 -04:00
// user settable parameters
static const struct AP_Param::GroupInfo var_info[];
protected:
// update_throttle_rpy_mix - updates thr_low_comp value towards the target
void update_throttle_rpy_mix();
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;
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)
};