AP_MotorsSingle: remove output_disarmed

This commit is contained in:
Leonard Hall 2016-01-18 14:20:58 +09:00 committed by Randy Mackay
parent 46ab198ebc
commit 4db73d86af
2 changed files with 0 additions and 8 deletions

View File

@ -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

View File

@ -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