From 9e86f4dc432e554a861d39a8184856b043059f33 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 4 Mar 2022 16:41:48 +0000 Subject: [PATCH] AP_Vehicle: add AC_Fence --- libraries/AP_Vehicle/AP_Vehicle.cpp | 13 +++++++++++++ libraries/AP_Vehicle/AP_Vehicle.h | 5 +++++ 2 files changed, 18 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 401f2de7d9..497df2f5f9 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -93,6 +93,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { AP_SUBGROUPINFO(ais, "AIS_", 13, AP_Vehicle, AP_AIS), #endif +#if AC_FENCE + // @Group: FENCE_ + // @Path: ../AC_Fence/AC_Fence.cpp + AP_SUBGROUPINFO(fence, "FENCE_", 14, AP_Vehicle, AC_Fence), +#endif + AP_GROUPEND }; @@ -232,6 +238,10 @@ void AP_Vehicle::setup() ais.init(); #endif +#if AC_FENCE + fence.init(); +#endif + custom_rotations.init(); gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready"); @@ -325,6 +335,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #if HAL_INS_ACCELCAL_ENABLED SCHED_TASK(accel_cal_update, 10, 100, 245), #endif +#if AC_FENCE + SCHED_TASK_CLASS(AC_Fence, &vehicle.fence, update, 10, 100, 248), +#endif #if AP_AIS_ENABLED SCHED_TASK_CLASS(AP_AIS, &vehicle.ais, update, 5, 100, 249), #endif diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 7a6e0b0502..dc3c1982cd 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -53,6 +53,7 @@ #include #include #include +#include class AP_Vehicle : public AP_HAL::HAL::Callbacks { @@ -397,6 +398,10 @@ protected: AP_AIS ais; #endif +#if AC_FENCE + AC_Fence fence; +#endif + static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Scheduler::Task scheduler_tasks[];