mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Avoidance: params always use set method
This commit is contained in:
parent
d423f483a6
commit
2f7f187e18
@ -95,8 +95,8 @@ public:
|
|||||||
void update();
|
void update();
|
||||||
|
|
||||||
// enable or disable avoidance
|
// enable or disable avoidance
|
||||||
void enable() { _enabled = true; };
|
void enable() { _enabled.set(true); };
|
||||||
void disable() { _enabled = false; };
|
void disable() { _enabled.set(false); };
|
||||||
|
|
||||||
// current overall threat level
|
// current overall threat level
|
||||||
MAV_COLLISION_THREAT_LEVEL current_threat_level() const;
|
MAV_COLLISION_THREAT_LEVEL current_threat_level() const;
|
||||||
|
Loading…
Reference in New Issue
Block a user