mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: use HAL_LOGGING_ENABLED in place of HAL_BOOTLOADER_BUILD
bootloader already disables GCS, so we can rely on HAL_GCS_ENABLED in place of HAL_BOOTLOADER_BUILD
This commit is contained in:
parent
cd1e1273fa
commit
a82b7f20c9
|
@ -37,7 +37,8 @@
|
|||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||
#include <AP_OpenDroneID/AP_OpenDroneID.h>
|
||||
#endif
|
||||
#ifndef HAL_BOOTLOADER_BUILD
|
||||
#include <AP_Logger/AP_Logger_config.h>
|
||||
#if HAL_LOGGING_ENABLED
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
#endif
|
||||
|
||||
|
@ -267,6 +268,7 @@ uint64_t Util::get_hw_rtc() const
|
|||
#if AP_BOOTLOADER_FLASHING_ENABLED
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#define Debug(fmt, args ...) do { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } while (0)
|
||||
#endif // HAL_GCS_ENABLED
|
||||
|
||||
|
@ -761,7 +763,7 @@ bool Util::get_true_random_vals(uint8_t* data, size_t size, uint32_t timeout_us)
|
|||
*/
|
||||
void Util::log_stack_info(void)
|
||||
{
|
||||
#if !defined(HAL_BOOTLOADER_BUILD) && HAL_LOGGING_ENABLED
|
||||
#if HAL_LOGGING_ENABLED
|
||||
static thread_t *last_tp;
|
||||
static uint8_t thread_id;
|
||||
thread_t *tp = last_tp;
|
||||
|
|
Loading…
Reference in New Issue