mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_MotorsCoax: remove output_disarmed
This commit is contained in:
parent
3df52aad5f
commit
5cb44901ff
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user