mirror of https://github.com/ArduPilot/ardupilot
AP_Param: fixed some compiler warnings
* added comment * replaced "~0" with the appropriate macro * resolved -Wconversion * saved some space by modifying AP_Param::add_vector_suffix (writing behind buffer could happen, if buffer_size is almost uint16_max but this can surely be ignored) further reading: http://stackoverflow.com/questions/809227/is-it-safe-to-use-1-to-set-all-bits-to-true
This commit is contained in:
parent
ab311d1dd4
commit
27a5c28851
|
@ -443,7 +443,8 @@ uint8_t AP_Param::type_size(enum ap_var_type type)
|
|||
// scan the EEPROM looking for a given variable by header content
|
||||
// return true if found, along with the offset in the EEPROM where
|
||||
// the variable is stored
|
||||
// if not found return the offset of the sentinal, or
|
||||
// if not found return the offset of the sentinal
|
||||
// if the sentinal isn't found either, the offset is set to __UINT16_MAX__
|
||||
bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
|
||||
{
|
||||
struct Param_header phdr;
|
||||
|
@ -468,31 +469,28 @@ bool AP_Param::scan(const AP_Param::Param_header *target, uint16_t *pofs)
|
|||
}
|
||||
ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
|
||||
}
|
||||
*pofs = ~0;
|
||||
*pofs = __UINT16_MAX__;
|
||||
serialDebug("scan past end of eeprom");
|
||||
return false;
|
||||
}
|
||||
|
||||
// add a X,Y,Z suffix to the name of a Vector3f element
|
||||
/**
|
||||
* add a _X, _Y, _Z suffix to the name of a Vector3f element
|
||||
* @param buffer
|
||||
* @param buffer_size
|
||||
* @param idx Suffix: 0 --> _X; 1 --> _Y; 2 --> _Z; (other --> undefined)
|
||||
*/
|
||||
void AP_Param::add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const
|
||||
{
|
||||
uint8_t len = strnlen(buffer, buffer_size);
|
||||
if ((size_t)(len+2) > buffer_size) {
|
||||
// the suffix doesn't fit
|
||||
return;
|
||||
}
|
||||
const size_t len = strnlen(buffer, buffer_size);
|
||||
if (len + 2 <= buffer_size) {
|
||||
buffer[len] = '_';
|
||||
if (idx == 0) {
|
||||
buffer[len+1] = 'X';
|
||||
} else if (idx == 1) {
|
||||
buffer[len+1] = 'Y';
|
||||
} else if (idx == 2) {
|
||||
buffer[len+1] = 'Z';
|
||||
}
|
||||
if ((size_t)(len+2) < buffer_size) {
|
||||
buffer[len + 1] = static_cast<char>('X' + idx);
|
||||
if (len + 3 <= buffer_size) {
|
||||
buffer[len + 2] = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Copy the variable's whole name to the supplied buffer.
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue