mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: only include NavEKF on fast CPUs
This commit is contained in:
parent
4adf6000f3
commit
006b9da6be
@ -285,7 +285,9 @@ static AP_YawController yawController(ahrs, aparm);
|
|||||||
static AP_SteerController steerController(ahrs);
|
static AP_SteerController steerController(ahrs);
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
static NavEKF NavEKF(ahrs, barometer);
|
static NavEKF NavEKF(ahrs, barometer);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||||
SITL sitl;
|
SITL sitl;
|
||||||
@ -805,7 +807,9 @@ static void ahrs_update()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
ahrs.update();
|
ahrs.update();
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
NavEKF.UpdateFilter();
|
NavEKF.UpdateFilter();
|
||||||
|
#endif
|
||||||
|
|
||||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
@ -530,6 +530,7 @@ static void NOINLINE send_simstate(mavlink_channel_t chan)
|
|||||||
// report NavEKF state
|
// report NavEKF state
|
||||||
static void NOINLINE send_ekf(mavlink_channel_t chan)
|
static void NOINLINE send_ekf(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
Vector3f euler;
|
Vector3f euler;
|
||||||
struct Location loc;
|
struct Location loc;
|
||||||
NavEKF.getEulerAngles(euler);
|
NavEKF.getEulerAngles(euler);
|
||||||
@ -541,6 +542,7 @@ static void NOINLINE send_ekf(mavlink_channel_t chan)
|
|||||||
loc.alt*1.0e-2f,
|
loc.alt*1.0e-2f,
|
||||||
loc.lat,
|
loc.lat,
|
||||||
loc.lng);
|
loc.lng);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||||
|
@ -203,6 +203,7 @@ struct PACKED log_EKF {
|
|||||||
// Write an EKF packet
|
// Write an EKF packet
|
||||||
static void Log_Write_EKF(void)
|
static void Log_Write_EKF(void)
|
||||||
{
|
{
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
Vector3f euler;
|
Vector3f euler;
|
||||||
struct Location loc;
|
struct Location loc;
|
||||||
NavEKF.getEulerAngles(euler);
|
NavEKF.getEulerAngles(euler);
|
||||||
@ -218,6 +219,7 @@ static void Log_Write_EKF(void)
|
|||||||
lon : loc.lng
|
lon : loc.lng
|
||||||
};
|
};
|
||||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
struct PACKED log_Performance {
|
struct PACKED log_Performance {
|
||||||
|
@ -241,7 +241,9 @@ static void init_home()
|
|||||||
guided_WP.alt += g.RTL_altitude_cm;
|
guided_WP.alt += g.RTL_altitude_cm;
|
||||||
|
|
||||||
// startup EKF now we have home
|
// startup EKF now we have home
|
||||||
|
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
|
||||||
NavEKF.InitialiseFilter();
|
NavEKF.InitialiseFilter();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user