SingleCopter: output_test for individual motors

Based on original work by Nils Hogberg
This commit is contained in:
Randy Mackay 2014-04-28 16:30:02 +09:00
parent 3610cfe24c
commit 07766e55f9
2 changed files with 38 additions and 46 deletions

View File

@ -216,50 +216,40 @@ void AP_MotorsSingle::output_disarmed()
output_min();
}
// output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction
void AP_MotorsSingle::output_test()
// output_test - spin a motor at the pwm value specified
// 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_MotorsSingle::output_test(uint8_t motor_seq, int16_t pwm)
{
// Send minimum values to all motors
output_min();
// exit immediately if not armed
if (!_flags.armed) {
return;
}
// spin main motor
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), _rc_throttle.radio_min + _min_throttle);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), _rc_throttle.radio_min);
hal.scheduler->delay(2000);
// flap servo 1
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_min);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_max);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), _servo1.radio_trim);
hal.scheduler->delay(2000);
// 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);
hal.scheduler->delay(2000);
// flap servo 3
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_min);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_max);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo3.radio_trim);
hal.scheduler->delay(2000);
// flap servo 4
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_min);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_max);
hal.scheduler->delay(1000);
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), _servo4.radio_trim);
// Send minimum values to all motors
output_min();
// output to motors and servos
switch (motor_seq) {
case 1:
// flap servo 1
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_1]), pwm);
break;
case 2:
// flap servo 2
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_2]), pwm);
break;
case 3:
// flap servo 3
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), pwm);
break;
case 4:
// flap servo 4
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_4]), pwm);
break;
case 5:
// spin main motor
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_7]), pwm);
break;
default:
// do nothing
break;
}
}

View File

@ -44,8 +44,10 @@ public:
// enable - starts allowing signals to be sent to motors
virtual void enable();
// output_test - spin each motor for a moment to allow the user to confirm the motor order and spin direction
virtual void output_test();
// output_test - spin a motor at the pwm value specified
// 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
virtual void output_min();