Copter Motors: use _min_throttle in output_test

This commit is contained in:
Randy Mackay 2013-05-31 14:31:56 +09:00
parent 28f2f87b26
commit 76028fc9d3
2 changed files with 4 additions and 4 deletions

View File

@ -477,7 +477,7 @@ void AP_MotorsMatrix::output_test()
for( j=0; j<AP_MOTORS_MAX_NUM_MOTORS; j++ ) { for( j=0; j<AP_MOTORS_MAX_NUM_MOTORS; j++ ) {
if( motor_enabled[j] && _test_order[j] == i ) { if( motor_enabled[j] && _test_order[j] == i ) {
// turn on this motor and wait 1/3rd of a second // turn on this motor and wait 1/3rd of a second
hal.rcout->write(_motor_to_channel_map[j], _rc_throttle->radio_min + 100); hal.rcout->write(_motor_to_channel_map[j], _rc_throttle->radio_min + _min_throttle);
hal.scheduler->delay(300); hal.scheduler->delay(300);
hal.rcout->write(_motor_to_channel_map[j], _rc_throttle->radio_min); hal.rcout->write(_motor_to_channel_map[j], _rc_throttle->radio_min);
hal.scheduler->delay(2000); hal.scheduler->delay(2000);

View File

@ -172,17 +172,17 @@ void AP_MotorsTri::output_test()
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _rc_throttle->radio_min); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _rc_throttle->radio_min);
hal.scheduler->delay(4000); hal.scheduler->delay(4000);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _rc_throttle->radio_min + 100); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _rc_throttle->radio_min + _min_throttle);
hal.scheduler->delay(300); hal.scheduler->delay(300);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _rc_throttle->radio_min); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _rc_throttle->radio_min);
hal.scheduler->delay(2000); hal.scheduler->delay(2000);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _rc_throttle->radio_min + 100); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _rc_throttle->radio_min + _min_throttle);
hal.scheduler->delay(300); hal.scheduler->delay(300);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _rc_throttle->radio_min); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _rc_throttle->radio_min);
hal.scheduler->delay(2000); hal.scheduler->delay(2000);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _rc_throttle->radio_min + 100); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _rc_throttle->radio_min + _min_throttle);
hal.scheduler->delay(300); hal.scheduler->delay(300);
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], motor_out[AP_MOTORS_MOT_1]); hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], motor_out[AP_MOTORS_MOT_1]);