Skip to content

Commit

Permalink
SITL: support up to 32 rotors in a frame
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge authored and peterbarker committed Jan 6, 2025
1 parent 592031c commit bb96db5
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 5 deletions.
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_Frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -409,7 +409,7 @@ void Frame::load_frame_params(const char *model_json)
};
char label_name[20];
for (uint8_t i=0; i<ARRAY_SIZE(per_motor_vars); i++) {
for (uint8_t j=0; j<12; j++) {
for (uint8_t j=0; j<SIM_FRAME_MAX_ACTUATORS; j++) {
snprintf(label_name, 20, "motor%i_%s", j+1, per_motor_vars[i].label);
auto v = obj->get(label_name);
if (v.is<AP_JSON::null>()) {
Expand Down
11 changes: 7 additions & 4 deletions libraries/SITL/SIM_Frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,10 @@
#include "SIM_Motor.h"
#include <AP_JSON/AP_JSON.h>

#ifndef SIM_FRAME_MAX_ACTUATORS
#define SIM_FRAME_MAX_ACTUATORS 32
#endif

namespace SITL {

/*
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit bb96db5

Please sign in to comment.