Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def config_option(self):
Feature('AHRS', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro wind compensation', 0, None),

Feature('Safety', 'PARACHUTE', 'HAL_PARACHUTE_ENABLED', 'Enable Parachute', 0, None),
Feature('Safety', 'FENCE', 'AP_FENCE_ENABLED', 'Enable Geofences', 2, None),
Feature('Safety', 'FENCE', 'AP_FENCE_ENABLED', 'Enable Geofences', 1, None),
Feature('Safety', 'RALLY', 'HAL_RALLY_ENABLED', 'Enable Rally points', 0, None), # noqa
Feature('Safety', 'AC_AVOID', 'AP_AVOIDANCE_ENABLED', 'Enable Object Avoidance', 0, 'FENCE'),
Feature('Safety', 'AC_OAPATHPLANNER', 'AP_OAPATHPLANNER_ENABLED', 'Enable Object Avoidance Path Planner', 0, 'FENCE'),
Expand Down
53 changes: 0 additions & 53 deletions libraries/AC_Fence/AC_Fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,6 @@
#if AP_FENCE_ENABLED

#include <AP_Vehicle/AP_Vehicle_Type.h>

#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) | (AP_FENCE_ENABLED == 1)))
#endif

#if !AC_FENCE_DUMMY_METHODS_ENABLED

#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Logger/AP_Logger.h>
Expand Down Expand Up @@ -1110,52 +1103,6 @@ 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() {};

uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable) { return 0; }

void AC_Fence::enable_floor() {}
void AC_Fence::disable_floor() {}
void AC_Fence::update() {}

void AC_Fence::auto_enable_fence_after_takeoff() {}
void AC_Fence::auto_enable_fence_on_arming() {}
void AC_Fence::auto_disable_fence_on_disarming() {}

uint8_t AC_Fence::present() const { return 0; }

uint8_t AC_Fence::get_enabled_fences() const { return 0; }

bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { return true; }

uint8_t AC_Fence::check(bool disable_auto_fences) { 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; }
bool AC_Fence::get_breach_direction_NED(uint8_t fence_type, Vector3f& direction, Location& fence_check_pos) const { return false; }
void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg) { }
void AC_Fence::print_fence_message(const char* msg, uint8_t fences) const {}

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;

Expand Down
6 changes: 1 addition & 5 deletions libraries/AC_Fence/AC_Fence_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,12 +4,8 @@

#include <GCS_MAVLink/GCS_config.h>

// Enabled 0 is compiled out
// Enabled 1 is always enabled on all vehicles
// Enabled 2 is enabled with dummy methods for tracker and blimp

#ifndef AP_FENCE_ENABLED
#define AP_FENCE_ENABLED 2
#define AP_FENCE_ENABLED 1
#endif

// CODE_REMOVAL
Expand Down
37 changes: 0 additions & 37 deletions libraries/AC_Fence/AC_PolyFence_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,7 @@

#if AP_FENCE_ENABLED

#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_BoardConfig/AP_BoardConfig.h>

#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) | (AP_FENCE_ENABLED == 1)))
#endif

#if !AC_FENCE_DUMMY_METHODS_ENABLED

#include <AP_AHRS/AP_AHRS.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>
Expand Down Expand Up @@ -1687,33 +1679,4 @@ 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 &center_pos_cm, float &radius) const { return false; }
bool AC_PolyFence_loader::get_inclusion_circle(uint8_t index, Vector2f &center_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, float& distance_outside_fence, Vector2f& fence_direction) 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
#endif // AP_FENCE_ENABLED
Loading