mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: add options param on plane
This commit is contained in:
parent
83b544dd0c
commit
259e70b2b1
|
@ -134,6 +134,13 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast<uint8_t>(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE),
|
AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast<uint8_t>(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE),
|
||||||
|
|
||||||
|
// @Param{Plane}: OPTIONS
|
||||||
|
// @DisplayName: Fence options
|
||||||
|
// @Description: 0:Disable mode change following fence action until fence breach is cleared
|
||||||
|
// @Bitmask: 0:Disable mode change following fence action until fence breach is cleared
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO_FRAME("OPTIONS", 11, AC_Fence, _options, static_cast<uint16_t>(OPTIONS::DISABLE_MODE_CHANGE), AP_PARAM_FRAME_PLANE),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -146,6 +146,13 @@ public:
|
||||||
AC_PolyFence_loader &polyfence();
|
AC_PolyFence_loader &polyfence();
|
||||||
const AC_PolyFence_loader &polyfence() const;
|
const AC_PolyFence_loader &polyfence() const;
|
||||||
|
|
||||||
|
enum class OPTIONS {
|
||||||
|
DISABLE_MODE_CHANGE = 1 << 0,
|
||||||
|
};
|
||||||
|
bool option_enabled(OPTIONS opt) const {
|
||||||
|
return (_options.get() & int16_t(opt)) != 0;
|
||||||
|
}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
@ -186,6 +193,7 @@ private:
|
||||||
AP_Int8 _total; // number of polygon points saved in eeprom
|
AP_Int8 _total; // number of polygon points saved in eeprom
|
||||||
AP_Int8 _ret_rally; // return to fence return point or rally point/home
|
AP_Int8 _ret_rally; // return to fence return point or rally point/home
|
||||||
AP_Int16 _ret_altitude; // return to this altitude
|
AP_Int16 _ret_altitude; // return to this altitude
|
||||||
|
AP_Int16 _options; // options bitmask, see OPTIONS enum
|
||||||
|
|
||||||
// backup fences
|
// backup fences
|
||||||
float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
|
float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
|
||||||
|
|
Loading…
Reference in New Issue