mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: quieten imu's on esp32
less noisy ins debug imu
This commit is contained in:
parent
46bc6d5122
commit
a896ab9e71
|
@ -40,9 +40,19 @@ extern const AP_HAL::HAL& hal;
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef INS_TIMING_DEBUG
|
||||
#include <stdio.h>
|
||||
#define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
|
||||
#else
|
||||
#define timing_printf(fmt, args...)
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
// hal.console can be accessed from bus threads on ChibiOS
|
||||
#define debug(fmt, args ...) do {hal.console->printf("MPU: " fmt "\n", ## args); } while(0)
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_ESP32
|
||||
// esp32 commonly has timing issues
|
||||
#define debug(fmt, args ...) do {timing_printf("MPU: " fmt "\n", ## args); } while(0)
|
||||
#else
|
||||
#define debug(fmt, args ...) do {printf("MPU: " fmt "\n", ## args); } while(0)
|
||||
#endif
|
||||
|
|
|
@ -27,9 +27,19 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifdef INS_TIMING_DEBUG
|
||||
#include <stdio.h>
|
||||
#define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
|
||||
#else
|
||||
#define timing_printf(fmt, args...)
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
// hal.console can be accessed from bus threads on ChibiOS
|
||||
#define debug(fmt, args ...) do {hal.console->printf("INV2: " fmt "\n", ## args); } while(0)
|
||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_ESP32
|
||||
// esp32 commonly has timing issues
|
||||
#define debug(fmt, args ...) do {timing_printf("INV2: " fmt "\n", ## args); } while(0)
|
||||
#else
|
||||
#define debug(fmt, args ...) do {printf("INV2: " fmt "\n", ## args); } while(0)
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue