AP_MotorsCoax: remove output_disarmed

This commit is contained in:
Leonard Hall 2016-01-18 14:20:45 +09:00 committed by Randy Mackay
parent 3df52aad5f
commit 5cb44901ff
2 changed files with 0 additions and 8 deletions

View File

@ -178,13 +178,6 @@ void AP_MotorsCoax::output_armed_stabilizing()
hal.rcout->push();
}
// output_disarmed - sends commands to the motors
void AP_MotorsCoax::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

@ -59,7 +59,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