CoaxCopter: output_test for individual motors

Based on original work by Nils Hogberg
This commit is contained in:
Randy Mackay 2014-04-28 16:29:30 +09:00
parent d63d82ec17
commit 8f74f5b3b0
2 changed files with 34 additions and 37 deletions

View File

@ -206,41 +206,36 @@ void AP_MotorsCoax::output_disarmed()
output_min(); output_min();
} }
// output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction // output_test - spin a motor at the pwm value specified
void AP_MotorsCoax::output_test() // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
void AP_MotorsCoax::output_test(uint8_t motor_seq, int16_t pwm)
{ {
// Send minimum values to all motors // exit immediately if not armed
output_min(); if (!_flags.armed) {
return;
}
// spin motor 1 // output to motors and servos
hal.scheduler->delay(1000); switch (motor_seq) {
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _rc_throttle.radio_min + _min_throttle); case 1:
hal.scheduler->delay(1000); // flap servo 1
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _rc_throttle.radio_min); hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), pwm);
hal.scheduler->delay(2000); break;
case 2:
// spin motor 2 // flap servo 2
hal.scheduler->delay(1000); hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), pwm);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _rc_throttle.radio_min + _min_throttle); break;
hal.scheduler->delay(1000); case 3:
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _rc_throttle.radio_min); // motor 1
hal.scheduler->delay(2000); hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), pwm);
break;
// flap servo 1 case 4:
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_min); // motor 2
hal.scheduler->delay(1000); hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), pwm);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_max); break;
hal.scheduler->delay(1000); default:
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_trim); // do nothing
hal.scheduler->delay(2000); break;
}
// flap servo 2
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_min);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_max);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), _servo2.radio_trim);
// Send minimum values to all motors
output_min();
} }

View File

@ -42,8 +42,10 @@ 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();
// output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction // output_test - spin a motor at the pwm value specified
virtual void output_test(); // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
virtual void output_test(uint8_t motor_seq, int16_t pwm);
// output_min - sends minimum values out to the motors // output_min - sends minimum values out to the motors
virtual void output_min(); virtual void output_min();