Tri: call output_min at end of motors test

Minor change to comments
This commit is contained in:
Randy Mackay 2013-11-27 21:57:32 +09:00
parent 9f2086baf2
commit ccedf98238
2 changed files with 7 additions and 7 deletions

View File

@ -69,7 +69,8 @@ void AP_MotorsTri::output_min()
{ {
// set lower limit flag // set lower limit flag
limit.throttle_lower = true; limit.throttle_lower = true;
// fill the motor_out[] array for HIL use
// set all motors to minimum
motor_out[AP_MOTORS_MOT_1] = _rc_throttle->radio_min; motor_out[AP_MOTORS_MOT_1] = _rc_throttle->radio_min;
motor_out[AP_MOTORS_MOT_2] = _rc_throttle->radio_min; motor_out[AP_MOTORS_MOT_2] = _rc_throttle->radio_min;
motor_out[AP_MOTORS_MOT_4] = _rc_throttle->radio_min; motor_out[AP_MOTORS_MOT_4] = _rc_throttle->radio_min;
@ -114,7 +115,7 @@ void AP_MotorsTri::output_armed()
// Every thing is limited // Every thing is limited
limit.throttle_lower = true; limit.throttle_lower = true;
}else{ }else{
int16_t roll_out = (float)_rc_roll->pwm_out * 0.866f; int16_t roll_out = (float)_rc_roll->pwm_out * 0.866f;
int16_t pitch_out = _rc_pitch->pwm_out / 2; int16_t pitch_out = _rc_pitch->pwm_out / 2;
@ -190,7 +191,7 @@ void AP_MotorsTri::output_disarmed()
output_min(); output_min();
} }
// output_disarmed - sends commands to the motors // output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction
void AP_MotorsTri::output_test() void AP_MotorsTri::output_test()
{ {
// Send minimum values to all motors // Send minimum values to all motors
@ -211,7 +212,6 @@ void AP_MotorsTri::output_test()
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], _rc_throttle->radio_min + _min_throttle); 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]); // Send minimum values to all motors
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_2], motor_out[AP_MOTORS_MOT_2]); output_min();
hal.rcout->write(_motor_to_channel_map[AP_MOTORS_MOT_4], motor_out[AP_MOTORS_MOT_4]);
} }

View File

@ -33,7 +33,7 @@ public:
// enable - starts allowing signals to be sent to motors // enable - starts allowing signals to be sent to motors
virtual void enable(); virtual void enable();
// motor test // output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction
virtual void output_test(); virtual void output_test();
// output_min - sends minimum values out to the motors // output_min - sends minimum values out to the motors