Skip to content

Commit

Permalink
Plane: Quadplane: check for valid RC before passing throttle to outputs
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Nov 25, 2023
1 parent ee59247 commit 22c6270
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 4 deletions.
6 changes: 4 additions & 2 deletions ArduPlane/motor_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,11 @@ void QuadPlane::motor_test_output()
pwm = motor_test.throttle_value;
break;

case MOTOR_TEST_THROTTLE_PILOT:
pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * plane.get_throttle_input()*0.01f;
case MOTOR_TEST_THROTTLE_PILOT: {
const float throttle_input = rc().has_valid_input() ? plane.get_throttle_input() : 0.0;
pwm = thr_min_pwm + (thr_max_pwm - thr_min_pwm) * throttle_input*0.01f;
break;
}

default:
motor_test_stop();
Expand Down
6 changes: 4 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -879,10 +879,12 @@ void QuadPlane::run_esc_calibration(void)
}
AP_Notify::flags.esc_calibration = true;
switch (esc_calibration) {
case 1:
case 1: {
// throttle based calibration
motors->set_throttle_passthrough_for_esc_calibration(plane.get_throttle_input() * 0.01f);
const float throttle_input = rc().has_valid_input() ? plane.get_throttle_input() : 0.0;
motors->set_throttle_passthrough_for_esc_calibration(throttle_input * 0.01f);
break;
}
case 2:
// full range calibration
motors->set_throttle_passthrough_for_esc_calibration(1);
Expand Down

0 comments on commit 22c6270

Please sign in to comment.