From f4d94806e591813e42c43caf40b7e448cc19edb5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 18 Feb 2016 12:05:10 +0900 Subject: [PATCH] AP_MotorsMatrix: remove output_min This is now implemented by parent AP_MotorsMulticopter --- libraries/AP_Motors/AP_MotorsMatrix.cpp | 15 --------------- libraries/AP_Motors/AP_MotorsMatrix.h | 3 --- 2 files changed, 18 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index 69482262b6..06044851d7 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -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; ipush(); -} - void AP_MotorsMatrix::output_to_motors() { int8_t i; diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 44a6f3eaca..958eb00935 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -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();