mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AC_PrecLand: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
78daf8911b
commit
26b665ed82
@ -310,11 +310,13 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
|
|||||||
// check the status of the landing target location
|
// check the status of the landing target location
|
||||||
check_target_status(rangefinder_alt_m, rangefinder_alt_valid);
|
check_target_status(rangefinder_alt_m, rangefinder_alt_valid);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (now - last_log_ms > 40) { // 25Hz
|
if (now - last_log_ms > 40) { // 25Hz
|
||||||
last_log_ms = now;
|
last_log_ms = now;
|
||||||
Write_Precland();
|
Write_Precland();
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// check the status of the target
|
// check the status of the target
|
||||||
@ -740,6 +742,7 @@ void AC_PrecLand::run_output_prediction()
|
|||||||
_last_valid_target_ms = AP_HAL::millis();
|
_last_valid_target_ms = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// Write a precision landing entry
|
// Write a precision landing entry
|
||||||
void AC_PrecLand::Write_Precland()
|
void AC_PrecLand::Write_Precland()
|
||||||
{
|
{
|
||||||
@ -773,6 +776,7 @@ void AC_PrecLand::Write_Precland()
|
|||||||
};
|
};
|
||||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
AC_PrecLand *AC_PrecLand::_singleton;
|
AC_PrecLand *AC_PrecLand::_singleton;
|
||||||
|
Loading…
Reference in New Issue
Block a user