mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_Motors: add get_throttle_warn function
This commit is contained in:
parent
e1be814853
commit
348001e786
@ -179,6 +179,9 @@ public:
|
|||||||
// get_throttle_limit - throttle limit ratio
|
// get_throttle_limit - throttle limit ratio
|
||||||
float get_throttle_limit() { return _throttle_limit; }
|
float get_throttle_limit() { return _throttle_limit; }
|
||||||
|
|
||||||
|
// returns warning throttle
|
||||||
|
float get_throttle_warn() { return rel_pwm_to_thr_range(_spin_when_armed); }
|
||||||
|
|
||||||
// 1 if motor is enabled, 0 otherwise
|
// 1 if motor is enabled, 0 otherwise
|
||||||
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS];
|
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user