Browse Source

Copter Motors: use _min_throttle in output_test

master
Randy Mackay 12 years ago
parent
commit
76028fc9d3
  1. 2
      libraries/AP_Motors/AP_MotorsMatrix.cpp
  2. 6
      libraries/AP_Motors/AP_MotorsTri.cpp

2
libraries/AP_Motors/AP_MotorsMatrix.cpp

@ -477,7 +477,7 @@ void AP_MotorsMatrix::output_test() @@ -477,7 +477,7 @@ void AP_MotorsMatrix::output_test()
for( j=0; j<AP_MOTORS_MAX_NUM_MOTORS; j++ ) {
if( motor_enabled[j] && _test_order[j] == i ) {
// 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.rcout->write(_motor_to_channel_map[j], _rc_throttle->radio_min);
hal.scheduler->delay(2000);

6
libraries/AP_Motors/AP_MotorsTri.cpp

@ -172,17 +172,17 @@ void AP_MotorsTri::output_test() @@ -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.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.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], _rc_throttle->radio_min);
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.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], _rc_throttle->radio_min);
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.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_1], motor_out[AP_MOTORS_MOT_1]);

Loading…
Cancel
Save