mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_MotorsSingle: remove output_disarmed
This commit is contained in:
parent
46ab198ebc
commit
4db73d86af
@ -191,13 +191,6 @@ void AP_MotorsSingle::output_armed_stabilizing()
|
|||||||
hal.rcout->push();
|
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
|
// 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
|
// 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
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
||||||
|
@ -60,7 +60,6 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
// output - sends commands to the motors
|
// output - sends commands to the motors
|
||||||
void output_armed_stabilizing();
|
void output_armed_stabilizing();
|
||||||
void output_disarmed();
|
|
||||||
|
|
||||||
AP_Int8 _rev_roll; // REV Roll feedback
|
AP_Int8 _rev_roll; // REV Roll feedback
|
||||||
AP_Int8 _rev_pitch; // REV pitch feedback
|
AP_Int8 _rev_pitch; // REV pitch feedback
|
||||||
|
Loading…
Reference in New Issue
Block a user