AP_Param: make count_parameters() thread safe

This commit is contained in:
Andrew Tridgell 2017-04-29 14:05:26 +10:00
parent 49b18819ce
commit 60e4c0eb98
1 changed files with 8 additions and 4 deletions

View File

@ -1984,21 +1984,25 @@ void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8
}
/*
return count of all scalar parameters
return count of all scalar parameters.
Note that this function may be called from the IO thread, so needs
to be thread safe
*/
uint16_t AP_Param::count_parameters(void)
{
// if we haven't cached the parameter count yet...
if (0 == _parameter_count) {
uint16_t ret = _parameter_count;
if (0 == ret) {
AP_Param *vp;
AP_Param::ParamToken token;
vp = AP_Param::first(&token, nullptr);
do {
_parameter_count++;
ret++;
} while (nullptr != (vp = AP_Param::next_scalar(&token, nullptr)));
_parameter_count = ret;
}
return _parameter_count;
return ret;
}
/*