mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
SITL: SIM_Frame: add number of motors to json spec
This commit is contained in:
parent
f864d93140
commit
f61d96dd5c
@ -411,6 +411,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||
FRAME_VAR(disc_area),
|
||||
FRAME_VAR(mdrag_coef),
|
||||
{"moment_inertia", &model.moment_of_inertia, VarType::VECTOR3F},
|
||||
FRAME_VAR(num_motors),
|
||||
};
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(vars); i++) {
|
||||
@ -523,6 +524,10 @@ void Frame::init(const char *frame_str, Battery *_battery)
|
||||
|
||||
battery->setup(model.battCapacityAh, model.refBatRes, model.maxVoltage);
|
||||
|
||||
if (uint8_t(model.num_motors) != num_motors) {
|
||||
::printf("Warning model expected %u motors and got %u\n", uint8_t(model.num_motors), num_motors);
|
||||
}
|
||||
|
||||
for (uint8_t i=0; i<num_motors; i++) {
|
||||
motors[i].setup_params(model.pwmMin, model.pwmMax, model.spin_min, model.spin_max, model.propExpo, model.slew_max,
|
||||
model.diagonal_size, power_factor, model.maxVoltage, effective_prop_area, velocity_max,
|
||||
|
@ -144,6 +144,9 @@ private:
|
||||
Vector3f motor_thrust_vec[12];
|
||||
float yaw_factor[12] = {0};
|
||||
|
||||
// number of motors
|
||||
float num_motors = 4;
|
||||
|
||||
} default_model;
|
||||
|
||||
protected:
|
||||
|
Loading…
Reference in New Issue
Block a user