Sub: Fence moved to vehicle

This commit is contained in:
Iampete1 2022-03-04 16:36:54 +00:00 committed by Andrew Tridgell
parent 2b8958f931
commit 2d8b9f7cbe
6 changed files with 7 additions and 26 deletions

View File

@ -84,9 +84,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(one_hz_loop, 1, 100, 33),
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36),
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),
#if AC_FENCE == ENABLED
SCHED_TASK_CLASS(AC_Fence, &sub.fence, update, 10, 100, 42),
#endif
#if HAL_MOUNT_ENABLED
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45),
#endif
@ -250,7 +247,7 @@ void Sub::three_hz_loop()
#if AC_FENCE == ENABLED
// check if we have breached a fence
fence_check();
#endif // AC_FENCE_ENABLED
#endif // AP_FENCE_ENABLED
ServoRelayEvents.update_events();
}

View File

@ -543,12 +543,6 @@ const AP_Param::Info Sub::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
#if AVOIDANCE_ENABLED == ENABLED
// @Group: AVOID_
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
@ -742,6 +736,11 @@ void Sub::load_parameters()
AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false);
#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
}
void Sub::convert_old_parameters()

View File

@ -87,7 +87,7 @@ public:
k_param_pos_control, // Position Control
k_param_wp_nav, // Waypoint navigation
k_param_mission, // Mission library
k_param_fence, // Fence Library
k_param_fence_old, // only used for conversion
k_param_terrain, // Terrain database
k_param_rally, // Disabled
k_param_circle_nav, // Disabled

View File

@ -56,7 +56,6 @@
#include <AC_WPNav/AC_WPNav.h> // Waypoint navigation library
#include <AC_WPNav/AC_Loiter.h>
#include <AC_WPNav/AC_Circle.h> // circle navigation library
#include <AC_Fence/AC_Fence.h> // Fence library
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
#include <AP_Scheduler/PerfInfo.h> // loop perf monitoring
#include <AP_BattMonitor/AP_BattMonitor.h> // Battery monitor library
@ -344,11 +343,6 @@ private:
AP_Mount camera_mount;
#endif
// AC_Fence library to reduce fly-aways
#if AC_FENCE == ENABLED
AC_Fence fence;
#endif
#if AVOIDANCE_ENABLED == ENABLED
AC_Avoid avoid;
#endif

View File

@ -230,11 +230,6 @@
MASK_LOG_MOTBATT
#endif
// Enable/disable Fence
#ifndef AC_FENCE
#define AC_FENCE ENABLED
#endif
#ifndef AC_RALLY
#define AC_RALLY DISABLED
#endif

View File

@ -24,10 +24,6 @@ void Sub::init_ardupilot()
g2.gripper.init();
#endif
#if AC_FENCE == ENABLED
fence.init();
#endif
// initialise notify system
notify.init();