mirror of https://github.com/ArduPilot/ardupilot
Plane: Add EFI Support
This commit is contained in:
parent
00e3344321
commit
2b27cd2ce9
|
@ -106,6 +106,9 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
#if LANDING_GEAR_ENABLED == ENABLED
|
||||
SCHED_TASK(landing_gear_update, 5, 50),
|
||||
#endif
|
||||
#if EFI_ENABLED
|
||||
SCHED_TASK(efi_update, 10, 200)
|
||||
#endif
|
||||
};
|
||||
|
||||
constexpr int8_t Plane::_failsafe_priorities[7];
|
||||
|
@ -305,6 +308,13 @@ void Plane::compass_save()
|
|||
}
|
||||
}
|
||||
|
||||
void Plane::efi_update(void)
|
||||
{
|
||||
#if EFI_ENABLED
|
||||
g2.efi.update();
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
once a second update the airspeed calibration ratio
|
||||
*/
|
||||
|
|
|
@ -588,6 +588,7 @@ static const ap_message STREAM_EXTRA1_msgs[] = {
|
|||
MSG_PID_TUNING,
|
||||
MSG_LANDING,
|
||||
MSG_ESC_TELEMETRY,
|
||||
MSG_EFI_STATUS,
|
||||
};
|
||||
static const ap_message STREAM_EXTRA2_msgs[] = {
|
||||
MSG_VFR_HUD
|
||||
|
|
|
@ -1239,6 +1239,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("DSPOILER_AILMTCH", 21, ParametersG2, crow_flap_aileron_matching, 100),
|
||||
|
||||
#if EFI_ENABLED
|
||||
// @Group: EFI_
|
||||
// @Path: ../libraries/AP_EFI/AP_EFI.cpp
|
||||
AP_SUBGROUPINFO(efi, "EFI", 22, ParametersG2, AP_EFI),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -564,6 +564,11 @@ public:
|
|||
AP_Int8 crow_flap_weight_inner;
|
||||
AP_Int8 crow_flap_options;
|
||||
AP_Int8 crow_flap_aileron_matching;
|
||||
|
||||
#if EFI_ENABLED
|
||||
// EFI Engine Monitor
|
||||
AP_EFI efi;
|
||||
#endif
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -81,6 +81,7 @@
|
|||
#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
|
||||
|
@ -903,6 +904,7 @@ private:
|
|||
void read_rangefinder(void);
|
||||
void read_airspeed(void);
|
||||
void rpm_update(void);
|
||||
void efi_update(void);
|
||||
void init_ardupilot();
|
||||
void startup_ground(void);
|
||||
bool set_mode(Mode& new_mode, const ModeReason reason);
|
||||
|
|
|
@ -378,8 +378,6 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle)
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
setup output channels all non-manual modes
|
||||
*/
|
||||
|
@ -393,6 +391,9 @@ void Plane::set_servos_controlled(void)
|
|||
// convert 0 to 100% (or -100 to +100) into PWM
|
||||
int8_t min_throttle = aparm.throttle_min.get();
|
||||
int8_t max_throttle = aparm.throttle_max.get();
|
||||
|
||||
// apply idle governor
|
||||
g2.ice_control.update_idle_governor(min_throttle);
|
||||
|
||||
if (min_throttle < 0 && !allow_reverse_thrust()) {
|
||||
// reverse thrust is available but inhibited.
|
||||
|
|
|
@ -118,6 +118,11 @@ void Plane::init_ardupilot()
|
|||
}
|
||||
#endif
|
||||
|
||||
// init EFI monitoring
|
||||
#if EFI_ENABLED
|
||||
g2.efi.init();
|
||||
#endif
|
||||
|
||||
// give AHRS the airspeed sensor
|
||||
ahrs.set_airspeed(&airspeed);
|
||||
|
||||
|
|
|
@ -784,6 +784,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
|||
{ MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING},
|
||||
{ MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE},
|
||||
{ MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION},
|
||||
{ MAVLINK_MSG_ID_EFI_STATUS, MSG_EFI_STATUS},
|
||||
};
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
|
||||
|
|
Loading…
Reference in New Issue