mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
26b665ed82
commit
d28a867453
|
@ -121,7 +121,7 @@ void AC_Circle::set_center(const Location& center)
|
|||
} else {
|
||||
// failed to convert location so set to current position and log error
|
||||
set_center(_inav.get_position_neu_cm(), false);
|
||||
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
|
||||
}
|
||||
} else {
|
||||
// convert Location with alt-above-home, alt-above-origin or absolute alt
|
||||
|
@ -129,7 +129,7 @@ void AC_Circle::set_center(const Location& center)
|
|||
if (!center.get_vector_from_origin_NEU(circle_center_neu)) {
|
||||
// default to current position and log error
|
||||
circle_center_neu = _inav.get_position_neu_cm();
|
||||
AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT);
|
||||
}
|
||||
set_center(circle_center_neu, false);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue