mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsTri: remove output_disarmed
This commit is contained in:
parent
a2fdcfaf3f
commit
8c4d6d6fbe
|
@ -252,13 +252,6 @@ void AP_MotorsTri::output_armed_stabilizing()
|
|||
hal.rcout->push();
|
||||
}
|
||||
|
||||
// output_disarmed - sends commands to the motors
|
||||
void AP_MotorsTri::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
|
||||
|
|
|
@ -50,7 +50,6 @@ public:
|
|||
protected:
|
||||
// output - sends commands to the motors
|
||||
void output_armed_stabilizing();
|
||||
void output_disarmed();
|
||||
|
||||
// calc_yaw_radio_output - calculate final radio output for yaw channel
|
||||
int16_t calc_yaw_radio_output(); // calculate radio output for yaw servo, typically in range of 1100-1900
|
||||
|
|
Loading…
Reference in New Issue