AP_Param: fixed v.load() on a sub-element of a AP_Vector3f

this isn't actually used at the moment in APM, but we should get it
right in case someone does try to load a single element of a vector
This commit is contained in:
Andrew Tridgell 2012-02-28 09:42:34 +11:00
parent 34f1ebcfb4
commit 701da6c30f
1 changed files with 12 additions and 1 deletions

View File

@ -631,8 +631,19 @@ bool AP_Param::load(void)
return false; return false;
} }
if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
// only vector3f can have non-zero idx for now
return false;
}
AP_Param *ap;
ap = this;
if (idx != 0) {
ap = (AP_Param *)((uintptr_t)ap) - (idx*sizeof(float));
}
// found it // found it
eeprom_read_block(this, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type)); eeprom_read_block(ap, (void*)(ofs+sizeof(phdr)), type_size((enum ap_var_type)phdr.type));
return true; return true;
} }