AP_Motors: merge fixed from rebase

This commit is contained in:
Andrew Tridgell 2017-10-10 14:20:36 +11:00
parent 0d0f1d264b
commit fc237ee9a0
2 changed files with 0 additions and 15 deletions

View File

@ -62,17 +62,6 @@ void AP_MotorsHeli_Quad::set_update_rate( uint16_t speed_hz )
rc_set_freq(mask, _speed_hz);
}
// enable - starts allowing signals to be sent to motors
void AP_MotorsHeli_Quad::enable()
{
// enable output channels
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
rc_enable_ch(AP_MOTORS_MOT_1+i);
}
rc_enable_ch(AP_MOTORS_HELI_QUAD_RSC);
}
// init_outputs
bool AP_MotorsHeli_Quad::init_outputs()
{
@ -81,7 +70,6 @@ bool AP_MotorsHeli_Quad::init_outputs()
}
for (uint8_t i=0; i<AP_MOTORS_HELI_QUAD_NUM_MOTORS; i++) {
rc_enable_ch(AP_MOTORS_MOT_1+i);
_servo[i] = SRV_Channels::get_channel_for(SRV_Channel::Aux_servo_function_t(SRV_Channel::k_motor1+i), CH_1+i);
if (!_servo[i]) {
return false;

View File

@ -33,9 +33,6 @@ public:
// set_update_rate - set update rate to motors
void set_update_rate( uint16_t speed_hz ) override;
// enable - starts allowing signals to be sent to motors
void enable() override;
// output_test - spin a motor at the pwm value specified
void output_test(uint8_t motor_seq, int16_t pwm) override;