mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_MotorsHeli: add getters for rotor speed
This commit is contained in:
parent
8b917b82ee
commit
3ad6700c5d
@ -176,6 +176,12 @@ public:
|
||||
// set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
|
||||
void set_desired_rotor_speed(int16_t desired_speed) { _desired_rotor_speed = desired_speed; }
|
||||
|
||||
// get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
|
||||
int16_t get_desired_rotor_speed() const { return _desired_rotor_speed; }
|
||||
|
||||
// get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
|
||||
int16_t get_estimated_rotor_speed() { return _rotor_speed_estimate; }
|
||||
|
||||
// return true if the main rotor is up to speed
|
||||
bool rotor_runup_complete() const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user