Plane: Fence moved to vehicle

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

View File

@ -78,9 +78,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66),
SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150, 69),
SCHED_TASK_CLASS(AP_Notify, &plane.notify, update, 50, 300, 72),
#if AC_FENCE == ENABLED
SCHED_TASK_CLASS(AC_Fence, &plane.fence, update, 10, 100, 75),
#endif
SCHED_TASK(read_rangefinder, 50, 100, 78),
#if AP_ICENGINE_ENABLED
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81),

View File

@ -950,12 +950,6 @@ const AP_Param::Info Plane::var_info[] = {
// @Path: ../libraries/AP_Rally/AP_Rally.cpp
GOBJECT(rally, "RALLY_", AP_Rally),
#if AC_FENCE == ENABLED
// @Group: FENCE_
// @Path: ../libraries/AC_Fence/AC_Fence.cpp
GOBJECT(fence, "FENCE_", AC_Fence),
#endif
#if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
@ -1391,6 +1385,7 @@ void Plane::load_parameters(void)
}
}
#if AC_FENCE
enum ap_var_type ptype_fence_type;
AP_Int8 *fence_type_new = (AP_Int8*)AP_Param::find("FENCE_TYPE", &ptype_fence_type);
if (fence_type_new && !fence_type_new->configured()) {
@ -1475,6 +1470,7 @@ void Plane::load_parameters(void)
}
}
}
#endif // AC_FENCE
#if AP_TERRAIN_AVAILABLE
g.terrain_follow.convert_parameter_width(AP_PARAM_INT8);
@ -1526,5 +1522,10 @@ void Plane::load_parameters(void)
}
#endif // HAL_INS_NUM_HARMONIC_NOTCH_FILTERS
// PARAMETER_CONVERSION - Added: Mar-2022
#if AC_FENCE
AP_Param::convert_class(g.k_param_fence, &fence, fence.var_info, 0, 0, true);
#endif
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
}

View File

@ -350,7 +350,7 @@ public:
k_param_gcs4, // stream rates
k_param_gcs5, // stream rates
k_param_gcs6, // stream rates
k_param_fence, // vehicle fence
k_param_fence, // vehicle fence - unused
k_param_acro_yaw_rate,
};

View File

@ -97,10 +97,6 @@
#include "afs_plane.h"
#endif
#if AC_FENCE == ENABLED
#include <AC_Fence/AC_Fence.h>
#endif
// Local modules
#include "defines.h"
#include "mode.h"
@ -254,10 +250,6 @@ private:
AP_OSD osd;
#endif
#if AC_FENCE == ENABLED
AC_Fence fence;
#endif
ModeCircle mode_circle;
ModeStabilize mode_stabilize;
ModeTraining mode_training;

View File

@ -233,11 +233,6 @@
# define SCALING_SPEED 15.0
#endif
// use this to disable geo-fencing
#ifndef AC_FENCE
# define AC_FENCE ENABLED
#endif
// a digital pin to set high when the geo-fence triggers. Defaults
// to -1, which means don't activate a pin
#ifndef FENCE_TRIGGERED_PIN

View File

@ -17,7 +17,6 @@
#include <AC_AttitudeControl/AC_WeatherVane.h>
#include <AC_WPNav/AC_WPNav.h>
#include <AC_WPNav/AC_Loiter.h>
#include <AC_Fence/AC_Fence.h>
#include <AC_Avoidance/AC_Avoid.h>
#include <AP_Logger/LogStructure.h>
#include <AP_Proximity/AP_Proximity.h>

View File

@ -147,11 +147,6 @@ void Plane::init_ardupilot()
#if GRIPPER_ENABLED == ENABLED
g2.gripper.init();
#endif
// init fence
#if AC_FENCE == ENABLED
fence.init();
#endif
}
//********************************************************************************