ArduPlane: move EFI to AP_Vehicle
This commit is contained in:
parent
ce352410e1
commit
554e7f8d1c
@ -113,9 +113,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
SCHED_TASK(landing_gear_update, 5, 50),
|
||||
#endif
|
||||
#if HAL_EFI_ENABLED
|
||||
SCHED_TASK(efi_update, 10, 200),
|
||||
#endif
|
||||
};
|
||||
|
||||
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
@ -337,13 +334,6 @@ void Plane::compass_save()
|
||||
}
|
||||
}
|
||||
|
||||
void Plane::efi_update(void)
|
||||
{
|
||||
#if HAL_EFI_ENABLED
|
||||
g2.efi.update();
|
||||
#endif
|
||||
}
|
||||
|
||||
#if AP_AIRSPEED_AUTOCAL_ENABLE
|
||||
/*
|
||||
once a second update the airspeed calibration ratio
|
||||
|
@ -1142,11 +1142,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),
|
||||
|
||||
#if HAL_EFI_ENABLED
|
||||
// @Group: EFI
|
||||
// @Path: ../libraries/AP_EFI/AP_EFI.cpp
|
||||
AP_SUBGROUPINFO(efi, "EFI", 22, ParametersG2, AP_EFI),
|
||||
#endif
|
||||
|
||||
// 22 was EFI
|
||||
|
||||
// @Param: FWD_BAT_VOLT_MAX
|
||||
// @DisplayName: Forward throttle battery voltage compensation maximum voltage
|
||||
@ -1469,6 +1466,22 @@ void Plane::load_parameters(void)
|
||||
|
||||
g.use_reverse_thrust.convert_parameter_width(AP_PARAM_INT16);
|
||||
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Oct-2021
|
||||
#if HAL_EFI_ENABLED
|
||||
{
|
||||
// Find G2's Top Level Key
|
||||
AP_Param::ConversionInfo info;
|
||||
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
|
||||
return;
|
||||
}
|
||||
|
||||
const uint16_t old_index = 22; // Old parameter index in g2
|
||||
const uint16_t old_top_element = 86; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||
AP_Param::convert_class(info.old_key, &efi, efi.var_info, old_index, old_top_element, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
|
||||
|
@ -538,11 +538,6 @@ public:
|
||||
AP_Float fwd_thr_batt_voltage_min;
|
||||
AP_Int8 fwd_thr_batt_idx;
|
||||
|
||||
#if HAL_EFI_ENABLED
|
||||
// EFI Engine Monitor
|
||||
AP_EFI efi;
|
||||
#endif
|
||||
|
||||
#if OFFBOARD_GUIDED == ENABLED
|
||||
// guided yaw heading PID
|
||||
AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.2};
|
||||
|
@ -81,7 +81,6 @@
|
||||
#include <AP_Parachute/AP_Parachute.h>
|
||||
#include <AP_ADSB/AP_ADSB.h>
|
||||
#include <AP_ICEngine/AP_ICEngine.h>
|
||||
#include <AP_EFI/AP_EFI.h>
|
||||
#include <AP_Gripper/AP_Gripper.h>
|
||||
#include <AP_Landing/AP_Landing.h>
|
||||
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
|
||||
|
@ -86,11 +86,6 @@ void Plane::init_ardupilot()
|
||||
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
||||
AP::compass().init();
|
||||
|
||||
// init EFI monitoring
|
||||
#if HAL_EFI_ENABLED
|
||||
g2.efi.init();
|
||||
#endif
|
||||
|
||||
// GPS Initialization
|
||||
gps.set_log_gps_bit(MASK_LOG_GPS);
|
||||
gps.init(serial_manager);
|
||||
|
Loading…
Reference in New Issue
Block a user