Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SITL: support up to 32 rotors in a frame #29015

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
Loading