AP_Motors: tailsitter: add external min throttle limit

This commit is contained in:
Peter Hall 2021-11-14 19:16:22 +00:00 committed by Andrew Tridgell
parent 2ffebebddc
commit 1fde5b3ef1
2 changed files with 52 additions and 17 deletions

View File

@ -31,19 +31,13 @@ extern const AP_HAL::HAL& hal;
void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type frame_type)
{
// setup default motor and servo mappings
uint8_t chan;
_has_diff_thrust = SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) || SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft);
// right throttle defaults to servo output 1
SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleRight, CH_1);
if (SRV_Channels::find_channel(SRV_Channel::k_throttleRight, chan)) {
motor_enabled[chan] = true;
}
// left throttle defaults to servo output 2
SRV_Channels::set_aux_channel_default(SRV_Channel::k_throttleLeft, CH_2);
if (SRV_Channels::find_channel(SRV_Channel::k_throttleLeft, chan)) {
motor_enabled[chan] = true;
}
// right servo defaults to servo output 3
SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorRight, CH_3);
@ -53,7 +47,7 @@ void AP_MotorsTailsitter::init(motor_frame_class frame_class, motor_frame_type f
SRV_Channels::set_aux_channel_default(SRV_Channel::k_tiltMotorLeft, CH_4);
SRV_Channels::set_angle(SRV_Channel::k_tiltMotorLeft, SERVO_OUTPUT_RANGE);
_mav_type = MAV_TYPE_COAXIAL;
_mav_type = MAV_TYPE_VTOL_DUOROTOR;
// record successful initialisation if what we setup was the desired frame_class
set_initialised_ok(frame_class == MOTOR_FRAME_TAILSITTER);
@ -89,11 +83,13 @@ void AP_MotorsTailsitter::output_to_motors()
_actuator[0] = 0.0f;
_actuator[1] = 0.0f;
_actuator[2] = 0.0f;
_external_min_throttle = 0.0;
break;
case SpoolState::GROUND_IDLE:
set_actuator_with_slew(_actuator[0], actuator_spin_up_to_ground_idle());
set_actuator_with_slew(_actuator[1], actuator_spin_up_to_ground_idle());
set_actuator_with_slew(_actuator[2], actuator_spin_up_to_ground_idle());
_external_min_throttle = 0.0;
break;
case SpoolState::SPOOLING_UP:
case SpoolState::THROTTLE_UNLIMITED:
@ -142,6 +138,7 @@ void AP_MotorsTailsitter::output_armed_stabilizing()
float yaw_thrust; // yaw thrust input value, +/- 1.0
float throttle_thrust; // throttle thrust input value, 0.0 - 1.0
float thrust_max; // highest motor value
float thrust_min; // lowest motor value
float thr_adj = 0.0f; // the difference between the pilot's desired throttle and throttle_thrust_best_rpy
// apply voltage and air pressure compensation
@ -150,28 +147,51 @@ void AP_MotorsTailsitter::output_armed_stabilizing()
pitch_thrust = _pitch_in + _pitch_in_ff;
yaw_thrust = _yaw_in + _yaw_in_ff;
throttle_thrust = get_throttle() * compensation_gain;
const float max_boost_throttle = _throttle_avg_max * compensation_gain;
// sanity check throttle is above zero and below current limited throttle
if (throttle_thrust <= 0.0f) {
throttle_thrust = 0.0f;
// never boost above max, derived from throttle mix params
const float min_throttle_out = MIN(_external_min_throttle, max_boost_throttle);
const float max_throttle_out = _throttle_thrust_max * compensation_gain;
// sanity check throttle is above min and below current limited throttle
if (throttle_thrust <= min_throttle_out) {
throttle_thrust = min_throttle_out;
limit.throttle_lower = true;
}
if (throttle_thrust >= _throttle_thrust_max) {
throttle_thrust = _throttle_thrust_max;
if (throttle_thrust >= max_throttle_out) {
throttle_thrust = max_throttle_out;
limit.throttle_upper = true;
}
if (roll_thrust >= 1.0) {
// cannot split motor outputs by more than 1
roll_thrust = 1;
limit.roll = true;
}
// calculate left and right throttle outputs
_thrust_left = throttle_thrust + roll_thrust * 0.5f;
_thrust_right = throttle_thrust - roll_thrust * 0.5f;
// if max thrust is more than one reduce average throttle
thrust_max = MAX(_thrust_right,_thrust_left);
thrust_min = MIN(_thrust_right,_thrust_left);
if (thrust_max > 1.0f) {
// if max thrust is more than one reduce average throttle
thr_adj = 1.0f - thrust_max;
limit.throttle_upper = true;
limit.roll = true;
limit.pitch = true;
} else if (thrust_min < 0.0) {
// if min thrust is less than 0 increase average throttle
// but never above max boost
thr_adj = -thrust_min;
if ((throttle_thrust + thr_adj) > max_boost_throttle) {
thr_adj = MAX(max_boost_throttle - throttle_thrust, 0.0);
// in this case we throw away some roll output, it will be uneven
// constraining the lower motor more than the upper
// this unbalances torque, but motor torque should have significantly less control power than tilts / control surfaces
// so its worth keeping the higher roll control power at a minor cost to yaw
limit.roll = true;
}
limit.throttle_lower = true;
}
// Add adjustment to reduce average throttle
@ -181,7 +201,12 @@ void AP_MotorsTailsitter::output_armed_stabilizing()
_throttle = throttle_thrust;
// compensation_gain can never be zero
_throttle_out = _throttle / compensation_gain;
// ensure accurate representation of average throttle output, this value is used for notch tracking and control surface scaling
if (_has_diff_thrust) {
_throttle_out = (throttle_thrust + thr_adj) / compensation_gain;
} else {
_throttle_out = throttle_thrust / compensation_gain;
}
// thrust vectoring
_tilt_left = pitch_thrust - yaw_thrust;

View File

@ -33,6 +33,9 @@ public:
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
uint16_t get_motor_mask() override;
// Set by tailsitters using diskloading minumum outflow velocity limit
void set_min_throttle(float val) {_external_min_throttle = val;}
protected:
// calculate motor outputs
void output_armed_stabilizing() override;
@ -45,4 +48,11 @@ protected:
float _tilt_right; // -1..1
float _thrust_left; // 0..1
float _thrust_right; // 0..1
// Set by tailsitters using diskloading minumum outflow velocity limit
float _external_min_throttle;
// true if differential thrust is available
bool _has_diff_thrust;
};