From 3ee88fd8c7b3ee3fbabee0d40146f94a6dd4d232 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 18 Feb 2016 12:06:14 +0900 Subject: [PATCH] AP_MotorsCoax: remove output_min This is now implemented by parent AP_MotorsMulticopter --- libraries/AP_Motors/AP_MotorsCoax.cpp | 14 -------------- libraries/AP_Motors/AP_MotorsCoax.h | 3 --- 2 files changed, 17 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index bef2524315..c4e0ffedeb 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -112,20 +112,6 @@ void AP_MotorsCoax::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_MotorsCoax::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_MotorsCoax::output_to_motors() { switch (_multicopter_flags.spool_mode) { diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index f72c6e0bc9..ff74f1ccd8 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -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();