Browse Source

AP_MotorsSingle: remove output_min

This is now implemented by parent AP_MotorsMulticopter
master
Randy Mackay 9 years ago
parent
commit
8566a61660
  1. 14
      libraries/AP_Motors/AP_MotorsSingle.cpp
  2. 3
      libraries/AP_Motors/AP_MotorsSingle.h

14
libraries/AP_Motors/AP_MotorsSingle.cpp

@ -115,20 +115,6 @@ void AP_MotorsSingle::enable() @@ -115,20 +115,6 @@ void AP_MotorsSingle::enable()
rc_enable_ch(AP_MOTORS_MOT_6);
}
// output_min - sends minimum values out to the motor and trim values to the servos
void AP_MotorsSingle::output_min()
{
// send minimum value to each motor
hal.rcout->cork();
rc_write(AP_MOTORS_MOT_1, _servo1.radio_trim);
rc_write(AP_MOTORS_MOT_2, _servo2.radio_trim);
rc_write(AP_MOTORS_MOT_3, _servo3.radio_trim);
rc_write(AP_MOTORS_MOT_4, _servo4.radio_trim);
rc_write(AP_MOTORS_MOT_5, _throttle_radio_min);
rc_write(AP_MOTORS_MOT_6, _throttle_radio_min);
hal.rcout->push();
}
void AP_MotorsSingle::output_to_motors()
{
switch (_multicopter_flags.spool_mode) {

3
libraries/AP_Motors/AP_MotorsSingle.h

@ -46,9 +46,6 @@ public: @@ -46,9 +46,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…
Cancel
Save