mirror of https://github.com/ArduPilot/ardupilot
AP_Param: correct possible use of nullptr during param count
::first can return nullptr
This commit is contained in:
parent
ac283fb032
commit
32795f0a8f
|
@ -2095,10 +2095,11 @@ uint16_t AP_Param::count_parameters(void)
|
||||||
AP_Param *vp;
|
AP_Param *vp;
|
||||||
AP_Param::ParamToken token;
|
AP_Param::ParamToken token;
|
||||||
|
|
||||||
vp = AP_Param::first(&token, nullptr);
|
for (vp = AP_Param::first(&token, nullptr);
|
||||||
do {
|
vp != nullptr;
|
||||||
|
vp = AP_Param::next_scalar(&token, nullptr)) {
|
||||||
ret++;
|
ret++;
|
||||||
} while (nullptr != (vp = AP_Param::next_scalar(&token, nullptr)));
|
}
|
||||||
_parameter_count = ret;
|
_parameter_count = ret;
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
|
|
Loading…
Reference in New Issue