Browse Source

AC_Avoidance: add enabled and margin accessors

mission-4.1.18
Randy Mackay 5 years ago
parent
commit
0d032ecd86
  1. 6
      libraries/AC_Avoidance/AC_Avoid.h

6
libraries/AC_Avoidance/AC_Avoid.h

@ -35,6 +35,9 @@ public: @@ -35,6 +35,9 @@ public:
return _singleton;
}
// return true if any avoidance feature is enabled
bool enabled() const { return _enabled != AC_AVOID_DISABLED; }
/*
* Adjusts the desired velocity so that the vehicle can stop
* before the fence/object.
@ -76,6 +79,9 @@ public: @@ -76,6 +79,9 @@ public:
// kP should be non-zero for Copter which has a non-linear response
float get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const;
// return margin (in meters) that the vehicle should stay from objects
float get_margin() const { return _margin; }
static const struct AP_Param::GroupInfo var_info[];
private:

Loading…
Cancel
Save