Plane: compile in AC_PrecLand for scripting

This commit is contained in:
Andrew Tridgell 2024-03-13 13:02:16 +11:00 committed by Peter Barker
parent 43a29f66d0
commit 8d8234459c
6 changed files with 38 additions and 1 deletions

View File

@ -141,6 +141,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landing_gear_update, 5, 50, 159),
#endif
#if AC_PRECLAND_ENABLED
SCHED_TASK(precland_update, 400, 50, 160),
#endif
};
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
@ -953,4 +956,13 @@ bool Plane::flight_option_enabled(FlightOptions flight_option) const
return g2.flight_options & flight_option;
}
#if AC_PRECLAND_ENABLED
void Plane::precland_update(void)
{
// alt will be unused if we pass false through as the second parameter:
return g2.precland.update(rangefinder_state.height_estimate*100,
rangefinder_state.in_range && rangefinder_state.in_use);
}
#endif
AP_HAL_MAIN_CALLBACKS(&plane);

View File

@ -1259,7 +1259,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Bitmask: 0:Roll,1:Pitch,2:Yaw
// @User: Standard
AP_GROUPINFO("AUTOTUNE_AXES", 34, ParametersG2, axis_bitmask, 7),
#if AC_PRECLAND_ENABLED
// @Group: PLND_
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
AP_SUBGROUPINFO(precland, "PLND_", 35, ParametersG2, AC_PrecLand),
#endif
AP_GROUPEND
};

View File

@ -535,6 +535,10 @@ public:
AP_LandingGear landing_gear;
#endif
#if AC_PRECLAND_ENABLED
AC_PrecLand precland;
#endif
// crow flaps weighting
AP_Int8 crow_flap_weight_outer;
AP_Int8 crow_flap_weight_inner;

View File

@ -88,6 +88,11 @@
#include "AP_ExternalControl_Plane.h"
#endif
#include <AC_PrecLand/AC_PrecLand_config.h>
#if AC_PRECLAND_ENABLED
# include <AC_PrecLand/AC_PrecLand.h>
#endif
#include "GCS_Mavlink.h"
#include "GCS_Plane.h"
#include "quadplane.h"
@ -256,6 +261,10 @@ private:
AP_Rally rally;
#endif
#if AC_PRECLAND_ENABLED
void precland_update(void);
#endif
// returns a Location for a rally point or home; if
// HAL_RALLY_ENABLED is false, just home.
Location calc_best_rally_or_home_location(const Location &current_loc, float rtl_home_alt_amsl_cm) const;

View File

@ -153,6 +153,10 @@ void Plane::init_ardupilot()
#if AP_GRIPPER_ENABLED
g2.gripper.init();
#endif
#if AC_PRECLAND_ENABLED
g2.precland.init(scheduler.get_loop_rate_hz());
#endif
}
//********************************************************************************

View File

@ -29,6 +29,8 @@ def build(bld):
'AP_OSD',
'AC_AutoTune',
'AP_Follow',
'AC_PrecLand',
'AP_IRLock',
],
)