mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMatrix: remove output_disarmed
This commit is contained in:
parent
b965857229
commit
cdec8f3387
|
@ -255,13 +255,6 @@ void AP_MotorsMatrix::output_armed_stabilizing()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// output_disarmed - sends commands to the motors
|
|
||||||
void AP_MotorsMatrix::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
|
||||||
|
|
|
@ -66,7 +66,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();
|
|
||||||
|
|
||||||
// add_motor using raw roll, pitch, throttle and yaw factors
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
||||||
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
||||||
|
|
Loading…
Reference in New Issue