mirror of https://github.com/ArduPilot/ardupilot
AP_DAL: replace config_error with allocation_error
This commit is contained in:
parent
f5ee2a3a50
commit
756972a80b
|
@ -145,7 +145,7 @@ void AP_DAL::init_sensors(void)
|
|||
#endif
|
||||
|
||||
if (alloc_failed) {
|
||||
AP_BoardConfig::config_error("Unable to allocate DAL backends");
|
||||
AP_BoardConfig::allocation_error("Unable to allocate DAL backends");
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -27,7 +27,7 @@ AP_DAL_RangeFinder::AP_DAL_RangeFinder()
|
|||
}
|
||||
return;
|
||||
failed:
|
||||
AP_BoardConfig::config_error("Unable to allocate DAL backends");
|
||||
AP_BoardConfig::allocation_error("Unable to allocate DAL backends");
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue