Skip to content

Commit

Permalink
Rover: Fix sail motor test not being reachable
Browse files Browse the repository at this point in the history
CID: 325623
  • Loading branch information
WickedShell authored and rmackay9 committed Nov 6, 2018
1 parent e0d94ce commit 65af2bc
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 3 deletions.
4 changes: 2 additions & 2 deletions APMrover2/AP_MotorsUGV.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,7 @@ void AP_MotorsUGV::output(bool armed, float ground_speed, float dt)
bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct)
{
// check if the motor_seq is valid
if (motor_seq > MOTOR_TEST_THROTTLE_RIGHT) {
if (motor_seq >= MOTOR_TEST_LAST) {
return false;
}
pct = constrain_float(pct, -100.0f, 100.0f);
Expand Down Expand Up @@ -404,7 +404,7 @@ bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct)
}
break;
}
default:
case MOTOR_TEST_LAST:
return false;
}
SRV_Channels::calc_pwm();
Expand Down
3 changes: 2 additions & 1 deletion APMrover2/AP_MotorsUGV.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ class AP_MotorsUGV {
MOTOR_TEST_STEERING = 2,
MOTOR_TEST_THROTTLE_LEFT = 3,
MOTOR_TEST_THROTTLE_RIGHT = 4,
MOTOR_TEST_MAINSAIL = 5
MOTOR_TEST_MAINSAIL = 5,
MOTOR_TEST_LAST
};

// supported custom motor configurations
Expand Down

0 comments on commit 65af2bc

Please sign in to comment.