AP_MotorsTri: remove output_min
This is now implemented by parent AP_MotorsMulticopter
This commit is contained in:
parent
f4d94806e5
commit
8621774040
@ -118,18 +118,6 @@ void AP_MotorsTri::enable()
|
||||
rc_enable_ch(AP_MOTORS_CH_TRI_YAW);
|
||||
}
|
||||
|
||||
// output_min - sends minimum values out to the motors
|
||||
void AP_MotorsTri::output_min()
|
||||
{
|
||||
// send minimum value to each motor
|
||||
hal.rcout->cork();
|
||||
rc_write(AP_MOTORS_MOT_1, _throttle_radio_min);
|
||||
rc_write(AP_MOTORS_MOT_2, _throttle_radio_min);
|
||||
rc_write(AP_MOTORS_MOT_4, _throttle_radio_min);
|
||||
rc_write(AP_MOTORS_CH_TRI_YAW, _yaw_servo_trim);
|
||||
hal.rcout->push();
|
||||
}
|
||||
|
||||
void AP_MotorsTri::output_to_motors()
|
||||
{
|
||||
switch (_multicopter_flags.spool_mode) {
|
||||
|
@ -37,9 +37,6 @@ public:
|
||||
// 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();
|
||||
|
||||
// output_to_motors - sends minimum values out to the motors
|
||||
virtual void output_to_motors();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user