mirror of https://github.com/ArduPilot/ardupilot
AP_Param: make ptype in first() and next() optional
This commit is contained in:
parent
5c3e059eea
commit
7ffb9b462d
|
@ -558,7 +558,9 @@ AP_Param *AP_Param::first(uint32_t *token, enum ap_var_type *ptype)
|
||||||
if (_num_vars == 0) {
|
if (_num_vars == 0) {
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
if (ptype != NULL) {
|
||||||
*ptype = (enum ap_var_type)pgm_read_byte(&_var_info[0].type);
|
*ptype = (enum ap_var_type)pgm_read_byte(&_var_info[0].type);
|
||||||
|
}
|
||||||
return (AP_Param *)(pgm_read_pointer(&_var_info[0].ptr));
|
return (AP_Param *)(pgm_read_pointer(&_var_info[0].ptr));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -588,7 +590,9 @@ AP_Param *AP_Param::next_group(uint8_t vindex, const struct GroupInfo *group_inf
|
||||||
if (*found_current) {
|
if (*found_current) {
|
||||||
// got a new one
|
// got a new one
|
||||||
(*token) = ((uint32_t)GROUP_OFFSET(group_base, i, group_shift)<<16) | vindex;
|
(*token) = ((uint32_t)GROUP_OFFSET(group_base, i, group_shift)<<16) | vindex;
|
||||||
|
if (ptype != NULL) {
|
||||||
*ptype = (enum ap_var_type)type;
|
*ptype = (enum ap_var_type)type;
|
||||||
|
}
|
||||||
return (AP_Param*)(pgm_read_pointer(&_var_info[vindex].ptr) + pgm_read_word(&group_info[i].offset));
|
return (AP_Param*)(pgm_read_pointer(&_var_info[vindex].ptr) + pgm_read_word(&group_info[i].offset));
|
||||||
}
|
}
|
||||||
if (GROUP_OFFSET(group_base, i, group_shift) == (*token)>>16) {
|
if (GROUP_OFFSET(group_base, i, group_shift) == (*token)>>16) {
|
||||||
|
@ -625,7 +629,9 @@ AP_Param *AP_Param::next(uint32_t *token, enum ap_var_type *ptype)
|
||||||
} else {
|
} else {
|
||||||
// found the next one
|
// found the next one
|
||||||
(*token) = i;
|
(*token) = i;
|
||||||
|
if (ptype != NULL) {
|
||||||
*ptype = (enum ap_var_type)type;
|
*ptype = (enum ap_var_type)type;
|
||||||
|
}
|
||||||
return (AP_Param *)(pgm_read_pointer(&_var_info[i].ptr));
|
return (AP_Param *)(pgm_read_pointer(&_var_info[i].ptr));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -637,6 +643,10 @@ AP_Param *AP_Param::next(uint32_t *token, enum ap_var_type *ptype)
|
||||||
AP_Param *AP_Param::next_scalar(uint32_t *token, enum ap_var_type *ptype)
|
AP_Param *AP_Param::next_scalar(uint32_t *token, enum ap_var_type *ptype)
|
||||||
{
|
{
|
||||||
AP_Param *ap;
|
AP_Param *ap;
|
||||||
while ((ap = next(token, ptype)) != NULL && *ptype > AP_PARAM_FLOAT) ;
|
enum ap_var_type type;
|
||||||
|
while ((ap = next(token, &type)) != NULL && type > AP_PARAM_FLOAT) ;
|
||||||
|
if (ap != NULL && ptype != NULL) {
|
||||||
|
*ptype = type;
|
||||||
|
}
|
||||||
return ap;
|
return ap;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue