Copter: Fence moved to vehicle

This commit is contained in:
Iampete1 2022-03-04 16:36:07 +00:00 committed by Andrew Tridgell
parent 41b8728296
commit b988391455
6 changed files with 15 additions and 32 deletions

View File

@ -175,9 +175,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(three_hz_loop, 3, 75, 57),
SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75, 60),
SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90, 63),
#if AC_FENCE == ENABLED
SCHED_TASK_CLASS(AC_Fence, &copter.fence, update, 10, 100, 66),
#endif
#if PRECISION_LANDING == ENABLED
SCHED_TASK(update_precland, 400, 50, 69),
#endif
@ -579,7 +576,7 @@ void Copter::three_hz_loop()
#if AC_FENCE == ENABLED
// check if we have breached a fence
fence_check();
#endif // AC_FENCE_ENABLED
#endif // AP_FENCE_ENABLED
// update ch6 in flight tuning

View File

@ -119,9 +119,6 @@
#if MODE_FOLLOW_ENABLED == ENABLED
# include <AP_Follow/AP_Follow.h>
#endif
#if AC_FENCE == ENABLED
# include <AC_Fence/AC_Fence.h>
#endif
#if AP_TERRAIN_AVAILABLE
# include <AP_Terrain/AP_Terrain.h>
#endif
@ -160,6 +157,14 @@
#include <AP_Scripting/AP_Scripting.h>
#endif
#if AC_AVOID_ENABLED && !AP_FENCE_ENABLED
#error AC_Avoidance relies on AP_FENCE_ENABLED which is disabled
#endif
#if AC_OAPATHPLANNER_ENABLED && !AP_FENCE_ENABLED
#error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled
#endif
// Local modules
#ifdef USER_PARAMS_ENABLED
#include "UserParameters.h"
@ -482,11 +487,6 @@ private:
AP_Mount camera_mount;
#endif
// AC_Fence library to reduce fly-aways
#if AC_FENCE == ENABLED
AC_Fence fence;
#endif
#if AC_AVOID_ENABLED == ENABLED
AC_Avoid avoid;
#endif

View File

@ -611,12 +611,6 @@ const AP_Param::Info Copter::var_info[] = {
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
#if AC_FENCE == ENABLED
// @Group: FENCE_
// @Path: ../libraries/AC_Fence/AC_Fence.cpp
GOBJECT(fence, "FENCE_", AC_Fence),
#endif
// @Group: AVOID_
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
#if AC_AVOID_ENABLED == ENABLED
@ -1285,6 +1279,11 @@ void Copter::load_parameters(void)
g.rtl_altitude.convert_parameter_width(AP_PARAM_INT16);
#endif
// PARAMETER_CONVERSION - Added: Mar-2022
#if AP_FENCE_ENABLED
AP_Param::convert_class(g.k_param_fence_old, &fence, fence.var_info, 0, 0, true);
#endif
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
// setup AP_Param frame type flags

View File

@ -143,7 +143,7 @@ public:
k_param_gpslock_limit, // deprecated - remove
k_param_geofence_limit, // deprecated - remove
k_param_altitude_limit, // deprecated - remove
k_param_fence,
k_param_fence_old, // only used for conversion
k_param_gps_glitch, // deprecated
k_param_baro_glitch, // 71 - deprecated

View File

@ -622,11 +622,6 @@
// Fence, Rally and Terrain and AC_Avoidance defaults
//
// Enable/disable Fence
#ifndef AC_FENCE
#define AC_FENCE ENABLED
#endif
#ifndef AC_RALLY
#define AC_RALLY ENABLED
#endif
@ -643,10 +638,6 @@
#define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES
#endif
#if AC_AVOID_ENABLED && !AC_FENCE
#error AC_Avoidance relies on AC_FENCE which is disabled
#endif
#if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED
#error Follow Mode relies on AC_AVOID which is disabled
#endif

View File

@ -31,10 +31,6 @@ void Copter::init_ardupilot()
g2.gripper.init();
#endif
#if AC_FENCE == ENABLED
fence.init();
#endif
// init winch
#if WINCH_ENABLED == ENABLED
g2.winch.init();