From 4db73d86af69a11c5e0ff7cb2ab76f7e967fbe21 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 18 Jan 2016 14:20:58 +0900 Subject: [PATCH] AP_MotorsSingle: remove output_disarmed --- libraries/AP_Motors/AP_MotorsSingle.cpp | 7 ------- libraries/AP_Motors/AP_MotorsSingle.h | 1 - 2 files changed, 8 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 66c25b41b9..92ae176895 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -191,13 +191,6 @@ void AP_MotorsSingle::output_armed_stabilizing() hal.rcout->push(); } -// output_disarmed - sends commands to the motors -void AP_MotorsSingle::output_disarmed() -{ - // Send minimum values to all motors - output_min(); -} - // output_test - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 8d8ae40024..3b2448f5de 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -60,7 +60,6 @@ public: protected: // output - sends commands to the motors void output_armed_stabilizing(); - void output_disarmed(); AP_Int8 _rev_roll; // REV Roll feedback AP_Int8 _rev_pitch; // REV pitch feedback