mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Param: fixed a compiler warning with -Wsign-conversion
This commit is contained in:
parent
27a5c28851
commit
4a75351bd3
@ -920,7 +920,7 @@ AP_Param *AP_Param::next_group(uint8_t vindex, const struct GroupInfo *group_inf
|
|||||||
*ptype = AP_PARAM_FLOAT;
|
*ptype = AP_PARAM_FLOAT;
|
||||||
}
|
}
|
||||||
uintptr_t ofs = (uintptr_t)PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset);
|
uintptr_t ofs = (uintptr_t)PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset);
|
||||||
ofs += sizeof(float)*(token->idx-1);
|
ofs += sizeof(float)*(token->idx - 1u);
|
||||||
return (AP_Param *)ofs;
|
return (AP_Param *)ofs;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -948,7 +948,7 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype)
|
|||||||
if (ptype != NULL) {
|
if (ptype != NULL) {
|
||||||
*ptype = AP_PARAM_FLOAT;
|
*ptype = AP_PARAM_FLOAT;
|
||||||
}
|
}
|
||||||
return (AP_Param *)(((token->idx-1)*sizeof(float))+(uintptr_t)PGM_POINTER(&_var_info[i].ptr));
|
return (AP_Param *)(((token->idx - 1u)*sizeof(float))+(uintptr_t)PGM_POINTER(&_var_info[i].ptr));
|
||||||
}
|
}
|
||||||
|
|
||||||
if (type != AP_PARAM_GROUP) {
|
if (type != AP_PARAM_GROUP) {
|
||||||
|
Loading…
Reference in New Issue
Block a user