AP_MotorsMatrix: remove output_min

This is now implemented by parent AP_MotorsMulticopter
This commit is contained in:
Randy Mackay 2016-02-18 12:05:10 +09:00
parent b4b33db79b
commit f4d94806e5
2 changed files with 0 additions and 18 deletions

View File

@ -83,21 +83,6 @@ void AP_MotorsMatrix::enable()
}
}
// output_min - sends minimum values out to the motors
void AP_MotorsMatrix::output_min()
{
int8_t i;
// send output to each motor
hal.rcout->cork();
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) {
rc_write(i, _throttle_radio_min);
}
}
hal.rcout->push();
}
void AP_MotorsMatrix::output_to_motors()
{
int8_t i;

View File

@ -39,9 +39,6 @@ public:
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
void output_test(uint8_t motor_seq, int16_t pwm);
// output_min - sends minimum values out to the motors
void output_min();
// output_to_motors - sends minimum values out to the motors
void output_to_motors();