mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: move from HAL_NO_LOGGING to HAL_LOGGING_ENABLED
This commit is contained in:
parent
a61b6ebda8
commit
7d8c5757d6
|
@ -264,7 +264,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_NO_LOGGING
|
#if HAL_LOGGING_ENABLED
|
||||||
//stop logging
|
//stop logging
|
||||||
if (AP_Logger::get_singleton()) {
|
if (AP_Logger::get_singleton()) {
|
||||||
AP::logger().StopLogging();
|
AP::logger().StopLogging();
|
||||||
|
@ -387,7 +387,7 @@ void Scheduler::_monitor_thread(void *arg)
|
||||||
sched->delay(100);
|
sched->delay(100);
|
||||||
}
|
}
|
||||||
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
|
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
|
||||||
#ifndef HAL_NO_LOGGING
|
#if HAL_LOGGING_ENABLED
|
||||||
uint8_t log_wd_counter = 0;
|
uint8_t log_wd_counter = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -405,7 +405,7 @@ void Scheduler::_monitor_thread(void *arg)
|
||||||
if (loop_delay >= 200) {
|
if (loop_delay >= 200) {
|
||||||
// the main loop has been stuck for at least
|
// the main loop has been stuck for at least
|
||||||
// 200ms. Starting logging the main loop state
|
// 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;
|
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
||||||
if (AP_Logger::get_singleton()) {
|
if (AP_Logger::get_singleton()) {
|
||||||
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII",
|
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)
|
||||||
INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
|
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()) {
|
if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) {
|
||||||
log_wd_counter = 0;
|
log_wd_counter = 0;
|
||||||
// log watchdog message once a second
|
// log watchdog message once a second
|
||||||
|
@ -450,7 +450,7 @@ void Scheduler::_monitor_thread(void *arg)
|
||||||
pd.fault_lr,
|
pd.fault_lr,
|
||||||
pd.thread_name4);
|
pd.thread_name4);
|
||||||
}
|
}
|
||||||
#endif // HAL_NO_LOGGING
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
#ifndef IOMCU_FW
|
#ifndef IOMCU_FW
|
||||||
// setup GPIO interrupt quotas
|
// setup GPIO interrupt quotas
|
||||||
|
@ -501,7 +501,7 @@ void Scheduler::_io_thread(void* arg)
|
||||||
while (!sched->_hal_initialized) {
|
while (!sched->_hal_initialized) {
|
||||||
sched->delay_microseconds(1000);
|
sched->delay_microseconds(1000);
|
||||||
}
|
}
|
||||||
#ifndef HAL_NO_LOGGING
|
#if HAL_LOGGING_ENABLED
|
||||||
uint32_t last_sd_start_ms = AP_HAL::millis();
|
uint32_t last_sd_start_ms = AP_HAL::millis();
|
||||||
#endif
|
#endif
|
||||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||||
|
@ -513,11 +513,11 @@ void Scheduler::_io_thread(void* arg)
|
||||||
// run registered IO processes
|
// run registered IO processes
|
||||||
sched->_run_io();
|
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();
|
uint32_t now = AP_HAL::millis();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef HAL_NO_LOGGING
|
#if HAL_LOGGING_ENABLED
|
||||||
if (!hal.util->get_soft_armed()) {
|
if (!hal.util->get_soft_armed()) {
|
||||||
// if sdcard hasn't mounted then retry it every 3s in the IO
|
// if sdcard hasn't mounted then retry it every 3s in the IO
|
||||||
// thread when disarmed
|
// thread when disarmed
|
||||||
|
|
|
@ -134,7 +134,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -34,7 +34,7 @@ define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -130,7 +130,7 @@ define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -138,7 +138,7 @@ define HAL_UART_STACK_SIZE 0x200
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -112,7 +112,7 @@ define HAL_UART_STACK_SIZE 0x200
|
||||||
|
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -50,7 +50,7 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3
|
||||||
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
define HAL_PERIPH_ADSB_BAUD_DEFAULT 0
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
define HAL_USE_RTC FALSE
|
define HAL_USE_RTC FALSE
|
||||||
|
|
|
@ -40,7 +40,7 @@ define GPS_MAX_INSTANCES 1
|
||||||
define HAL_COMPASS_MAX_SENSORS 1
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
|
@ -104,7 +104,7 @@ define HAL_UART_STACK_SIZE 256
|
||||||
define STORAGE_THD_WA_SIZE 512
|
define STORAGE_THD_WA_SIZE 512
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -156,7 +156,7 @@ define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_PERIPH_ENABLE_GPS
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
|
|
|
@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 300
|
||||||
define IO_THD_WA_SIZE 300
|
define IO_THD_WA_SIZE 300
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -82,7 +82,7 @@ define STORAGE_THD_WA_SIZE 512
|
||||||
define IO_THD_WA_SIZE 512
|
define IO_THD_WA_SIZE 512
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
||||||
|
|
|
@ -105,7 +105,7 @@ define STORAGE_THD_WA_SIZE 512
|
||||||
define IO_THD_WA_SIZE 512
|
define IO_THD_WA_SIZE 512
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
||||||
|
|
|
@ -50,7 +50,7 @@ define DMA_RESERVE_SIZE 0
|
||||||
define HAL_DISABLE_LOOP_DELAY
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
define HAL_NO_GCS
|
define HAL_NO_GCS
|
||||||
define HAL_NO_LOGGING
|
define HAL_LOGGING_ENABLED 0
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
define HAL_MINIMIZE_FEATURES 0
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
|
@ -129,7 +129,7 @@ define HAL_USE_RTC FALSE
|
||||||
define HAL_NO_FLASH_SUPPORT TRUE
|
define HAL_NO_FLASH_SUPPORT TRUE
|
||||||
define HAL_NO_UARTDRIVER TRUE
|
define HAL_NO_UARTDRIVER TRUE
|
||||||
define DISABLE_SERIAL_ESC_COMM TRUE
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
||||||
define HAL_NO_LOGGING TRUE
|
define HAL_LOGGING_ENABLED 0
|
||||||
|
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
|
|
@ -233,7 +233,7 @@ void init()
|
||||||
|
|
||||||
void panic(const char *errormsg, ...)
|
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);
|
INTERNAL_ERROR(AP_InternalError::error_t::panic);
|
||||||
va_list ap;
|
va_list ap;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue