Rover: fix motor test for pilot passthrough of steering

This commit is contained in:
khancyr 2017-07-17 21:46:40 +09:00 committed by Randy Mackay
parent b6033df457
commit 2e451eb2bc
1 changed files with 1 additions and 1 deletions

View File

@ -41,7 +41,7 @@ void Rover::motor_test_output()
case MOTOR_TEST_THROTTLE_PILOT:
if ((AP_MotorsUGV::motor_test_order)motor_test_seq == AP_MotorsUGV::MOTOR_TEST_STEERING) {
test_result = g2.motors.output_test_pct((AP_MotorsUGV::motor_test_order)motor_test_seq, channel_steer->get_control_in());
test_result = g2.motors.output_test_pct((AP_MotorsUGV::motor_test_order)motor_test_seq, channel_steer->norm_input_dz() * 100.0f);
} else {
test_result = g2.motors.output_test_pct((AP_MotorsUGV::motor_test_order)motor_test_seq, channel_throttle->get_control_in());
}