mirror of https://github.com/ArduPilot/ardupilot
169 lines
6.7 KiB
C++
169 lines
6.7 KiB
C++
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
#include "AC_AttitudeControl_Multi.h"
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
// table of user settable parameters
|
|
const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
|
|
// parameters from parent vehicle
|
|
AP_NESTEDGROUPINFO(AC_AttitudeControl, 0),
|
|
|
|
// @Param: RAT_RLL_P
|
|
// @DisplayName: Roll axis rate controller P gain
|
|
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
|
|
// @Range: 0.08 0.30
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_RLL_I
|
|
// @DisplayName: Roll axis rate controller I gain
|
|
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
|
|
// @Range: 0.01 0.5
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_RLL_IMAX
|
|
// @DisplayName: Roll axis rate controller I gain maximum
|
|
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 1
|
|
// @Increment: 0.01
|
|
// @Units: Percent
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_RLL_D
|
|
// @DisplayName: Roll axis rate controller D gain
|
|
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
|
|
// @Range: 0.0 0.02
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_RLL_FILT
|
|
// @DisplayName: Roll axis rate conroller input frequency in Hz
|
|
// @Description: Roll axis rate conroller input frequency in Hz
|
|
// @Range: 1 100
|
|
// @Increment: 1
|
|
// @Units: Hz
|
|
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID),
|
|
|
|
// @Param: RAT_PIT_P
|
|
// @DisplayName: Pitch axis rate controller P gain
|
|
// @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
|
|
// @Range: 0.08 0.30
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_PIT_I
|
|
// @DisplayName: Pitch axis rate controller I gain
|
|
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
|
|
// @Range: 0.01 0.5
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_PIT_IMAX
|
|
// @DisplayName: Pitch axis rate controller I gain maximum
|
|
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 1
|
|
// @Increment: 0.01
|
|
// @Units: Percent
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_PIT_D
|
|
// @DisplayName: Pitch axis rate controller D gain
|
|
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
|
|
// @Range: 0.0 0.02
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_PIT_FILT
|
|
// @DisplayName: Pitch axis rate conroller input frequency in Hz
|
|
// @Description: Pitch axis rate conroller input frequency in Hz
|
|
// @Range: 1 100
|
|
// @Increment: 1
|
|
// @Units: Hz
|
|
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID),
|
|
|
|
// @Param: RAT_YAW_P
|
|
// @DisplayName: Yaw axis rate controller P gain
|
|
// @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
|
|
// @Range: 0.10 0.50
|
|
// @Increment: 0.005
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_YAW_I
|
|
// @DisplayName: Yaw axis rate controller I gain
|
|
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
|
|
// @Range: 0.010 0.05
|
|
// @Increment: 0.01
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_YAW_IMAX
|
|
// @DisplayName: Yaw axis rate controller I gain maximum
|
|
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
|
// @Range: 0 1
|
|
// @Increment: 0.01
|
|
// @Units: Percent
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_YAW_D
|
|
// @DisplayName: Yaw axis rate controller D gain
|
|
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
|
|
// @Range: 0.000 0.02
|
|
// @Increment: 0.001
|
|
// @User: Standard
|
|
|
|
// @Param: RAT_YAW_FILT
|
|
// @DisplayName: Yaw axis rate conroller input frequency in Hz
|
|
// @Description: Yaw axis rate conroller input frequency in Hz
|
|
// @Range: 1 100
|
|
// @Increment: 1
|
|
// @Units: Hz
|
|
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID),
|
|
|
|
AP_GROUPEND
|
|
};
|
|
|
|
AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS &ahrs, const AP_Vehicle::MultiCopter &aparm, AP_MotorsMulticopter& motors, float dt) :
|
|
AC_AttitudeControl(ahrs, aparm, motors, dt),
|
|
_motors_multi(motors),
|
|
_pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
|
|
_pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, dt),
|
|
_pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_YAW_FILT_HZ, dt)
|
|
{
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
}
|
|
|
|
// get lean angle max for pilot input that prioritises altitude hold over lean angle
|
|
float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
|
|
{
|
|
// calc maximum tilt angle based on throttle
|
|
float thr_max = _motors_multi.get_throttle_thrust_max();
|
|
|
|
// divide by zero check
|
|
if (is_zero(thr_max)) {
|
|
return 0.0f;
|
|
}
|
|
|
|
return ToDeg(acos(constrain_float(_throttle_in_filt.get()/(0.9f * thr_max), 0.0f, 1.0f))) * 100.0f;
|
|
}
|
|
|
|
// returns a throttle including compensation for roll/pitch angle
|
|
// throttle value should be 0 ~ 1
|
|
float AC_AttitudeControl_Multi::get_boosted_throttle(float throttle_in)
|
|
{
|
|
if (!_angle_boost_enabled) {
|
|
_angle_boost = 0;
|
|
return throttle_in;
|
|
}
|
|
// inverted_factor is 1 for tilt angles below 60 degrees
|
|
// inverted_factor reduces from 1 to 0 for tilt angles between 60 and 90 degrees
|
|
|
|
float cos_tilt = _ahrs.cos_pitch() * _ahrs.cos_roll();
|
|
float inverted_factor = constrain_float(2.0f*cos_tilt, 0.0f, 1.0f);
|
|
float boost_factor = 1.0f/constrain_float(cos_tilt, 0.5f, 1.0f);
|
|
|
|
float throttle_out = throttle_in*inverted_factor*boost_factor;
|
|
_angle_boost = constrain_float(throttle_out - throttle_in,-1.0f,1.0f);
|
|
return throttle_out;
|
|
}
|