From bb96db5466ea359139c34088f46d7b7239e1a381 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Jul 2024 11:14:43 +1000 Subject: [PATCH] SITL: support up to 32 rotors in a frame --- libraries/SITL/SIM_Frame.cpp | 2 +- libraries/SITL/SIM_Frame.h | 11 +++++++---- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index c3f2fba101295..e31bb817172df 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -409,7 +409,7 @@ void Frame::load_frame_params(const char *model_json) }; char label_name[20]; for (uint8_t i=0; iget(label_name); if (v.is()) { diff --git a/libraries/SITL/SIM_Frame.h b/libraries/SITL/SIM_Frame.h index a097943f6e5c4..1c5dba3c3256c 100644 --- a/libraries/SITL/SIM_Frame.h +++ b/libraries/SITL/SIM_Frame.h @@ -22,6 +22,10 @@ #include "SIM_Motor.h" #include +#ifndef SIM_FRAME_MAX_ACTUATORS +#define SIM_FRAME_MAX_ACTUATORS 32 +#endif + namespace SITL { /* @@ -132,10 +136,9 @@ class Frame { // if zero value will be estimated from mass Vector3f moment_of_inertia; - // if zero will no be used - Vector3f motor_pos[12]; - Vector3f motor_thrust_vec[12]; - float yaw_factor[12] = {0}; + Vector3f motor_pos[SIM_FRAME_MAX_ACTUATORS]; + Vector3f motor_thrust_vec[SIM_FRAME_MAX_ACTUATORS]; + float yaw_factor[SIM_FRAME_MAX_ACTUATORS] {0,}; // number of motors float num_motors = 4;