Browse Source

AP_HAL_ChibiOS: move from HAL_NO_LOGGING to HAL_LOGGING_ENABLED

c415-sdk
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
7d8c5757d6
  1. 16
      libraries/AP_HAL_ChibiOS/Scheduler.cpp
  2. 2
      libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat
  3. 2
      libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat
  4. 2
      libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat
  5. 2
      libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat
  6. 2
      libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat
  7. 2
      libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat
  8. 2
      libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat
  9. 2
      libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat
  10. 2
      libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat
  11. 2
      libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat
  12. 2
      libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat
  13. 2
      libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat
  14. 2
      libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat
  15. 2
      libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat
  16. 2
      libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat
  17. 2
      libraries/AP_HAL_ChibiOS/system.cpp

16
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -264,7 +264,7 @@ void Scheduler::reboot(bool hold_in_bootloader) @@ -264,7 +264,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
}
#endif
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
//stop logging
if (AP_Logger::get_singleton()) {
AP::logger().StopLogging();
@ -387,7 +387,7 @@ void Scheduler::_monitor_thread(void *arg) @@ -387,7 +387,7 @@ void Scheduler::_monitor_thread(void *arg)
sched->delay(100);
}
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
uint8_t log_wd_counter = 0;
#endif
@ -405,7 +405,7 @@ void Scheduler::_monitor_thread(void *arg) @@ -405,7 +405,7 @@ void Scheduler::_monitor_thread(void *arg)
if (loop_delay >= 200) {
// the main loop has been stuck for at least
// 200ms. Starting logging the main loop state
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
if (AP_Logger::get_singleton()) {
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII",
@ -428,7 +428,7 @@ void Scheduler::_monitor_thread(void *arg) @@ -428,7 +428,7 @@ void Scheduler::_monitor_thread(void *arg)
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
}
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) {
log_wd_counter = 0;
// log watchdog message once a second
@ -450,7 +450,7 @@ void Scheduler::_monitor_thread(void *arg) @@ -450,7 +450,7 @@ void Scheduler::_monitor_thread(void *arg)
pd.fault_lr,
pd.thread_name4);
}
#endif // HAL_NO_LOGGING
#endif // HAL_LOGGING_ENABLED
#ifndef IOMCU_FW
// setup GPIO interrupt quotas
@ -501,7 +501,7 @@ void Scheduler::_io_thread(void* arg) @@ -501,7 +501,7 @@ void Scheduler::_io_thread(void* arg)
while (!sched->_hal_initialized) {
sched->delay_microseconds(1000);
}
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
uint32_t last_sd_start_ms = AP_HAL::millis();
#endif
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
@ -513,11 +513,11 @@ void Scheduler::_io_thread(void* arg) @@ -513,11 +513,11 @@ void Scheduler::_io_thread(void* arg)
// run registered IO processes
sched->_run_io();
#if !defined(HAL_NO_LOGGING) || CH_DBG_ENABLE_STACK_CHECK == TRUE
#if HAL_LOGGING_ENABLED || CH_DBG_ENABLE_STACK_CHECK == TRUE
uint32_t now = AP_HAL::millis();
#endif
#ifndef HAL_NO_LOGGING
#if HAL_LOGGING_ENABLED
if (!hal.util->get_soft_armed()) {
// if sdcard hasn't mounted then retry it every 3s in the IO
// thread when disarmed

2
libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat

@ -134,7 +134,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0 @@ -134,7 +134,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat

@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1 @@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY

2
libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat

@ -34,7 +34,7 @@ define GPS_MAX_INSTANCES 1 @@ -34,7 +34,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY

2
libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat

@ -130,7 +130,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0 @@ -130,7 +130,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat

@ -138,7 +138,7 @@ define HAL_UART_STACK_SIZE 0x200 @@ -138,7 +138,7 @@ define HAL_UART_STACK_SIZE 0x200
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat

@ -112,7 +112,7 @@ define HAL_UART_STACK_SIZE 0x200 @@ -112,7 +112,7 @@ define HAL_UART_STACK_SIZE 0x200
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat

@ -50,7 +50,7 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3 @@ -50,7 +50,7 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_RTC FALSE

2
libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat

@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1 @@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY

2
libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat

@ -104,7 +104,7 @@ define HAL_UART_STACK_SIZE 256 @@ -104,7 +104,7 @@ define HAL_UART_STACK_SIZE 256
define STORAGE_THD_WA_SIZE 512
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat

@ -156,7 +156,7 @@ define HAL_BARO_ALLOW_INIT_NO_BARO @@ -156,7 +156,7 @@ define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_CAN_DEFAULT_NODE_ID 0
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_PERIPH_ENABLE_GPS

2
libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat

@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 300 @@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 300
define IO_THD_WA_SIZE 300
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat

@ -82,7 +82,7 @@ define STORAGE_THD_WA_SIZE 512 @@ -82,7 +82,7 @@ define STORAGE_THD_WA_SIZE 512
define IO_THD_WA_SIZE 512
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat

@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 512 @@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 512
define IO_THD_WA_SIZE 512
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat

@ -50,7 +50,7 @@ define DMA_RESERVE_SIZE 0 @@ -50,7 +50,7 @@ define DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
define HAL_NO_GCS
define HAL_NO_LOGGING
define HAL_LOGGING_ENABLED 0
define HAL_NO_MONITOR_THREAD
define HAL_MINIMIZE_FEATURES 0

2
libraries/AP_HAL_ChibiOS/hwdef/iomcu/hwdef.dat

@ -129,7 +129,7 @@ define HAL_USE_RTC FALSE @@ -129,7 +129,7 @@ define HAL_USE_RTC FALSE
define HAL_NO_FLASH_SUPPORT TRUE
define HAL_NO_UARTDRIVER TRUE
define DISABLE_SERIAL_ESC_COMM TRUE
define HAL_NO_LOGGING TRUE
define HAL_LOGGING_ENABLED 0
define DMA_RESERVE_SIZE 0

2
libraries/AP_HAL_ChibiOS/system.cpp

@ -233,7 +233,7 @@ void init() @@ -233,7 +233,7 @@ void init()
void panic(const char *errormsg, ...)
{
#if !defined(HAL_BOOTLOADER_BUILD) && !defined(HAL_NO_LOGGING)
#if !defined(HAL_BOOTLOADER_BUILD) && HAL_LOGGING_ENABLED
INTERNAL_ERROR(AP_InternalError::error_t::panic);
va_list ap;

Loading…
Cancel
Save