Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: tailsitter: do not run throttle when disarmed in Q modes #16908

Merged
merged 3 commits into from
Apr 26, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 7 additions & 7 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@
*****************************************/
void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
{
if (!(control_mode->does_auto_throttle() || quadplane.in_assisted_flight() || quadplane.in_vtol_mode())) {
// only do throttle slew limiting in modes where throttle control is automatic
return;
}

uint8_t slewrate = aparm.throttle_slewrate;
if (control_mode == &mode_auto) {
if (auto_state.takeoff_complete == false && g.takeoff_throttle_slewrate != 0) {
Expand Down Expand Up @@ -836,13 +841,8 @@ void Plane::set_servos(void)
// set airbrake outputs
airbrake_update();

if (control_mode->does_auto_throttle() ||
quadplane.in_assisted_flight() ||
quadplane.in_vtol_mode()) {
/* only do throttle slew limiting in modes where throttle
* control is automatic */
throttle_slew_limit(SRV_Channel::k_throttle);
}
// slew rate limit throttle
throttle_slew_limit(SRV_Channel::k_throttle);

if (!arming.is_armed()) {
//Some ESCs get noisy (beep error msgs) if PWM == 0.
Expand Down
3 changes: 0 additions & 3 deletions ArduPlane/tailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,11 +169,8 @@ void QuadPlane::tailsitter_output(void)
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, (motors->get_roll())*SERVO_MAX);

if (hal.util->get_soft_armed()) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, motors->thrust_to_actuator(motors->get_throttle()) * 100);
// scale surfaces for throttle
tailsitter_speed_scaling();
} else {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, motors->get_throttle() * 100);
}

tilt_left = 0.0f;
Expand Down
21 changes: 14 additions & 7 deletions libraries/AP_Motors/AP_MotorsTailsitter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,23 +86,30 @@ void AP_MotorsTailsitter::output_to_motors()

switch (_spool_state) {
case SpoolState::SHUT_DOWN:
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, get_pwm_output_min());
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, get_pwm_output_min());
_actuator[0] = 0.0f;
_actuator[1] = 0.0f;
_actuator[2] = 0.0f;
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());
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(actuator_spin_up_to_ground_idle()));
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(actuator_spin_up_to_ground_idle()));
set_actuator_with_slew(_actuator[2], actuator_spin_up_to_ground_idle());
break;
case SpoolState::SPOOLING_UP:
case SpoolState::THROTTLE_UNLIMITED:
case SpoolState::SPOOLING_DOWN:
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(thrust_to_actuator(_thrust_left)));
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(thrust_to_actuator(_thrust_right)));
set_actuator_with_slew(_actuator[0], thrust_to_actuator(_thrust_left));
set_actuator_with_slew(_actuator[1], thrust_to_actuator(_thrust_right));
set_actuator_with_slew(_actuator[2], thrust_to_actuator(_throttle));
break;
}

// Always output to tilt servos
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, output_to_pwm(_actuator[0]));
SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, output_to_pwm(_actuator[1]));

// use set scaled to allow a different PWM range on plane forward throttle, throttle range is 0 to 100
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, _actuator[2]*100);

SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorLeft, _tilt_left*SERVO_OUTPUT_RANGE);
SRV_Channels::set_output_scaled(SRV_Channel::k_tiltMotorRight, _tilt_right*SERVO_OUTPUT_RANGE);

Expand Down