mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_HAL_SITL: use ARRAY_SIZE macro
This commit is contained in:
parent
d4d56aef1a
commit
473415a3c2
@ -175,7 +175,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (model_str && home_str) {
|
if (model_str && home_str) {
|
||||||
for (uint8_t i=0; i<sizeof(model_constructors)/sizeof(model_constructors[0]); i++) {
|
for (uint8_t i=0; i < ARRAY_SIZE(model_constructors); i++) {
|
||||||
if (strncasecmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
|
if (strncasecmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) {
|
||||||
sitl_model = model_constructors[i].constructor(home_str, model_str);
|
sitl_model = model_constructors[i].constructor(home_str, model_str);
|
||||||
sitl_model->set_speedup(speedup);
|
sitl_model->set_speedup(speedup);
|
||||||
|
Loading…
Reference in New Issue
Block a user