mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_Params: fix seg fault in debug function
otherwise at start, when loading paramter is could fail at AP_Param.cpp:611, Debug("scan past end of eeprom")"
This commit is contained in:
parent
4daa4e9df9
commit
5aa4bc4368
@ -38,7 +38,7 @@ extern const AP_HAL::HAL &hal;
|
|||||||
#define ENABLE_DEBUG 1
|
#define ENABLE_DEBUG 1
|
||||||
|
|
||||||
#if ENABLE_DEBUG
|
#if ENABLE_DEBUG
|
||||||
# define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
||||||
#else
|
#else
|
||||||
# define Debug(fmt, args ...)
|
# define Debug(fmt, args ...)
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user