diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index c1196cc513..1504c8ec4e 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -2,6 +2,14 @@ #if AC_FENCE +#include + +#ifndef AC_FENCE_DUMMY_METHODS_ENABLED +#define AC_FENCE_DUMMY_METHODS_ENABLED !(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub)) +#endif + +#if !AC_FENCE_DUMMY_METHODS_ENABLED + #include #include #include @@ -695,6 +703,46 @@ const AC_PolyFence_loader &AC_Fence::polyfence() const return _poly_loader; } + +#else // build type is not appropriate; provide a dummy implementation: +const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND }; + +AC_Fence::AC_Fence() {}; + +void AC_Fence::enable(bool value) {}; + +void AC_Fence::disable_floor() {}; + +void AC_Fence::auto_enable_fence_after_takeoff() {}; +void AC_Fence::auto_disable_fence_for_landing() {}; + +bool AC_Fence::present() const { return false; } + +uint8_t AC_Fence::get_enabled_fences() const { return 0; } + +bool AC_Fence::pre_arm_check(const char* &fail_msg) const { return true; } + +uint8_t AC_Fence::check() { return 0; } +bool AC_Fence::check_destination_within_fence(const Location& loc) { return true; } +float AC_Fence::get_breach_distance(uint8_t fence_type) const { return 0.0; } + +void AC_Fence::manual_recovery_start() {} + +bool AC_Fence::sys_status_present() const { return false; } +bool AC_Fence::sys_status_enabled() const { return false; } +bool AC_Fence::sys_status_failed() const { return false; } + +AC_PolyFence_loader &AC_Fence::polyfence() +{ + return _poly_loader; +} +const AC_PolyFence_loader &AC_Fence::polyfence() const +{ + return _poly_loader; +} + +#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED + // singleton instance AC_Fence *AC_Fence::_singleton; diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index e2aac27ef4..d8d2b0bb09 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -1,4 +1,11 @@ #include "AC_PolyFence_loader.h" +#include + +#ifndef AC_FENCE_DUMMY_METHODS_ENABLED +#define AC_FENCE_DUMMY_METHODS_ENABLED !(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub)) +#endif + +#if !AC_FENCE_DUMMY_METHODS_ENABLED #include #include @@ -1662,3 +1669,32 @@ void AC_PolyFence_loader::update() return; } } + +#else // build type is not appropriate; provide a dummy implementation: + +void AC_PolyFence_loader::init() {}; + +bool AC_PolyFence_loader::get_item(const uint16_t seq, AC_PolyFenceItem &item) { return false; } + +Vector2f* AC_PolyFence_loader::get_exclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; } +Vector2f* AC_PolyFence_loader::get_inclusion_polygon(uint16_t index, uint16_t &num_points) const { return nullptr; } + +bool AC_PolyFence_loader::get_exclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; } +bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f ¢er_pos_cm, float &radius) const { return false; } + +void AC_PolyFence_loader::handle_msg(GCS_MAVLINK &link, const mavlink_message_t& msg) {}; + +bool AC_PolyFence_loader::breached() const { return false; } +bool AC_PolyFence_loader::breached(const Location& loc) const { return false; } + +uint16_t AC_PolyFence_loader::max_items() const { return 0; } + +bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_t count) { return false; } + +void AC_PolyFence_loader::update() {}; + +#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT +bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { return false; } +#endif + +#endif // #if AC_FENCE_DUMMY_METHODS_ENABLED