mirror of https://github.com/ArduPilot/ardupilot
Copter: allow NavEKFs to be compiled out
This commit is contained in:
parent
d95956a587
commit
e3dd0d33e7
|
@ -627,13 +627,17 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
|
||||
GOBJECT(rcmap, "RCMAP_", RCMapper),
|
||||
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
// @Group: EK2_
|
||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
|
||||
|
||||
#endif
|
||||
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
// @Group: EK3_
|
||||
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
||||
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
#endif
|
||||
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
// @Group: MIS_
|
||||
|
|
|
@ -198,7 +198,8 @@ void Copter::check_ekf_reset()
|
|||
AP::logger().Write_Event(LogEvent::EKF_YAW_RESET);
|
||||
}
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE && HAL_NAVEKF2_AVAILABLE
|
||||
|
||||
// check for change in primary EKF (log only, AC_WPNav handles position target adjustment)
|
||||
if ((ahrs.EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (ahrs.EKF2.getPrimaryCoreIndex() != -1)) {
|
||||
attitude_control->inertial_frame_reset();
|
||||
|
|
Loading…
Reference in New Issue