AP_GPS: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
52c806e32e
commit
fa8f3b5715
@ -2254,6 +2254,7 @@ bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const
|
||||
return true;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// Logging support:
|
||||
// Write an GPS packet
|
||||
void AP_GPS::Write_GPS(uint8_t i)
|
||||
@ -2310,6 +2311,7 @@ void AP_GPS::Write_GPS(uint8_t i)
|
||||
};
|
||||
AP::logger().WriteBlock(&pkt2, sizeof(pkt2));
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
get GPS based yaw
|
||||
|
@ -526,10 +526,12 @@ void AP_GPS_DroneCAN::handle_status_msg(const ardupilot_gnss_Status& msg)
|
||||
healthy = msg.healthy;
|
||||
status_flags = msg.status;
|
||||
if (error_code != msg.error_codes) {
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)",
|
||||
(unsigned int)(state.instance + 1),
|
||||
error_code,
|
||||
msg.error_codes);
|
||||
#endif
|
||||
error_code = msg.error_codes;
|
||||
}
|
||||
}
|
||||
|
@ -23,6 +23,7 @@
|
||||
#include <time.h>
|
||||
#include <AP_Common/time.h>
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
|
||||
#define GPS_BACKEND_DEBUGGING 0
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user