mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Param: disable debug code by default
found on EU dev call
This commit is contained in:
parent
119df09c44
commit
17f8b0b11a
@ -45,7 +45,7 @@ uint16_t AP_Param::sentinal_offset;
|
||||
// singleton instance
|
||||
AP_Param *AP_Param::_singleton;
|
||||
|
||||
#define ENABLE_DEBUG 1
|
||||
#define ENABLE_DEBUG 0
|
||||
|
||||
#if ENABLE_DEBUG
|
||||
# define Debug(fmt, args ...) do {::printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
||||
@ -2123,11 +2123,13 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass)
|
||||
AP_Param *vp = find(pname, &var_type);
|
||||
if (!vp) {
|
||||
if (last_pass) {
|
||||
#if ENABLE_DEBUG
|
||||
::printf("Ignored unknown param %s in defaults file %s\n",
|
||||
pname, filename);
|
||||
hal.console->printf(
|
||||
"Ignored unknown param %s in defaults file %s\n",
|
||||
pname, filename);
|
||||
#endif
|
||||
}
|
||||
continue;
|
||||
}
|
||||
@ -2319,11 +2321,13 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
|
||||
AP_Param *vp = find(pname, &var_type);
|
||||
if (!vp) {
|
||||
if (last_pass) {
|
||||
#if ENABLE_DEBUG
|
||||
::printf("Ignored unknown param %s from embedded region (offset=%u)\n",
|
||||
pname, unsigned(ptr - param_defaults_data.data));
|
||||
hal.console->printf(
|
||||
"Ignored unknown param %s from embedded region (offset=%u)\n",
|
||||
pname, unsigned(ptr - param_defaults_data.data));
|
||||
#endif
|
||||
}
|
||||
continue;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user