mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AR_PosControl: add accessor for reversed
This commit is contained in:
parent
d982c28ef2
commit
7d3f013695
@ -26,6 +26,9 @@ public:
|
|||||||
// set reversed
|
// set reversed
|
||||||
void set_reversed(bool reversed) { _reversed = reversed; }
|
void set_reversed(bool reversed) { _reversed = reversed; }
|
||||||
|
|
||||||
|
// accessor for _reversed
|
||||||
|
bool get_reversed() { return _reversed; }
|
||||||
|
|
||||||
// get limits
|
// get limits
|
||||||
float get_speed_max() const { return _speed_max; }
|
float get_speed_max() const { return _speed_max; }
|
||||||
float get_accel_max() const { return _accel_max; }
|
float get_accel_max() const { return _accel_max; }
|
||||||
|
Loading…
Reference in New Issue
Block a user