mirror of https://github.com/ArduPilot/ardupilot
SITL: SIM_Frame: fixed per_motor_vars config loading
This commit is contained in:
parent
3691fdadc8
commit
689a5c7b52
|
@ -413,7 +413,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
// use default value
|
// use default value
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (vars[i].t == VarType::FLOAT) {
|
if (per_motor_vars[i].t == VarType::FLOAT) {
|
||||||
parse_float(v, label_name, *(((float *)per_motor_vars[i].ptr) + j));
|
parse_float(v, label_name, *(((float *)per_motor_vars[i].ptr) + j));
|
||||||
|
|
||||||
} else if (per_motor_vars[i].t == VarType::VECTOR3F) {
|
} else if (per_motor_vars[i].t == VarType::VECTOR3F) {
|
||||||
|
|
Loading…
Reference in New Issue