mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
d28a867453
commit
7cf033efd9
@ -559,6 +559,7 @@ void AP_AHRS::update_EKF2(void)
|
|||||||
if (start_time_ms == 0) {
|
if (start_time_ms == 0) {
|
||||||
start_time_ms = AP_HAL::millis();
|
start_time_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// if we're doing Replay logging then don't allow any data
|
// if we're doing Replay logging then don't allow any data
|
||||||
// into the EKF yet. Don't allow it to block us for long.
|
// into the EKF yet. Don't allow it to block us for long.
|
||||||
if (!hal.util->was_watchdog_reset()) {
|
if (!hal.util->was_watchdog_reset()) {
|
||||||
@ -568,6 +569,7 @@ void AP_AHRS::update_EKF2(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
|
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
|
||||||
_ekf2_started = EKF2.InitialiseFilter();
|
_ekf2_started = EKF2.InitialiseFilter();
|
||||||
@ -626,6 +628,7 @@ void AP_AHRS::update_EKF3(void)
|
|||||||
if (start_time_ms == 0) {
|
if (start_time_ms == 0) {
|
||||||
start_time_ms = AP_HAL::millis();
|
start_time_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// if we're doing Replay logging then don't allow any data
|
// if we're doing Replay logging then don't allow any data
|
||||||
// into the EKF yet. Don't allow it to block us for long.
|
// into the EKF yet. Don't allow it to block us for long.
|
||||||
if (!hal.util->was_watchdog_reset()) {
|
if (!hal.util->was_watchdog_reset()) {
|
||||||
@ -635,6 +638,7 @@ void AP_AHRS::update_EKF3(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
|
if (AP_HAL::millis() - start_time_ms > startup_delay_ms) {
|
||||||
_ekf3_started = EKF3.InitialiseFilter();
|
_ekf3_started = EKF3.InitialiseFilter();
|
||||||
}
|
}
|
||||||
@ -2896,7 +2900,7 @@ bool AP_AHRS::set_home(const Location &loc)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && HAL_LOGGING_ENABLED
|
||||||
if (!_home_is_set) {
|
if (!_home_is_set) {
|
||||||
// record home is set
|
// record home is set
|
||||||
AP::logger().Write_Event(LogEvent::SET_HOME);
|
AP::logger().Write_Event(LogEvent::SET_HOME);
|
||||||
@ -2906,7 +2910,9 @@ bool AP_AHRS::set_home(const Location &loc)
|
|||||||
_home = tmp;
|
_home = tmp;
|
||||||
_home_is_set = true;
|
_home_is_set = true;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
Log_Write_Home_And_Origin();
|
Log_Write_Home_And_Origin();
|
||||||
|
#endif
|
||||||
|
|
||||||
// send new home and ekf origin to GCS
|
// send new home and ekf origin to GCS
|
||||||
GCS_SEND_MESSAGE(MSG_HOME);
|
GCS_SEND_MESSAGE(MSG_HOME);
|
||||||
|
@ -244,6 +244,7 @@ Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const
|
|||||||
bf.x * _sin_yaw + bf.y * _cos_yaw);
|
bf.x * _sin_yaw + bf.y * _cos_yaw);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log ahrs home and EKF origin
|
// log ahrs home and EKF origin
|
||||||
void AP_AHRS::Log_Write_Home_And_Origin()
|
void AP_AHRS::Log_Write_Home_And_Origin()
|
||||||
{
|
{
|
||||||
@ -260,6 +261,7 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
|||||||
Write_Origin(LogOriginType::ahrs_home, _home);
|
Write_Origin(LogOriginType::ahrs_home, _home);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// get apparent to true airspeed ratio
|
// get apparent to true airspeed ratio
|
||||||
float AP_AHRS_Backend::get_EAS2TAS(void) {
|
float AP_AHRS_Backend::get_EAS2TAS(void) {
|
||||||
|
@ -1,3 +1,7 @@
|
|||||||
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
#include "AP_AHRS.h"
|
#include "AP_AHRS.h"
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
@ -184,3 +188,5 @@ void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl
|
|||||||
AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC));
|
AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user