mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 01:58:29 -04:00
SITL: support up to 32 rotors in a frame
This commit is contained in:
parent
592031cc5f
commit
bb96db5466
@ -409,7 +409,7 @@ void Frame::load_frame_params(const char *model_json)
|
|||||||
};
|
};
|
||||||
char label_name[20];
|
char label_name[20];
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(per_motor_vars); i++) {
|
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);
|
snprintf(label_name, 20, "motor%i_%s", j+1, per_motor_vars[i].label);
|
||||||
auto v = obj->get(label_name);
|
auto v = obj->get(label_name);
|
||||||
if (v.is<AP_JSON::null>()) {
|
if (v.is<AP_JSON::null>()) {
|
||||||
|
@ -22,6 +22,10 @@
|
|||||||
#include "SIM_Motor.h"
|
#include "SIM_Motor.h"
|
||||||
#include <AP_JSON/AP_JSON.h>
|
#include <AP_JSON/AP_JSON.h>
|
||||||
|
|
||||||
|
#ifndef SIM_FRAME_MAX_ACTUATORS
|
||||||
|
#define SIM_FRAME_MAX_ACTUATORS 32
|
||||||
|
#endif
|
||||||
|
|
||||||
namespace SITL {
|
namespace SITL {
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -132,10 +136,9 @@ private:
|
|||||||
// if zero value will be estimated from mass
|
// if zero value will be estimated from mass
|
||||||
Vector3f moment_of_inertia;
|
Vector3f moment_of_inertia;
|
||||||
|
|
||||||
// if zero will no be used
|
Vector3f motor_pos[SIM_FRAME_MAX_ACTUATORS];
|
||||||
Vector3f motor_pos[12];
|
Vector3f motor_thrust_vec[SIM_FRAME_MAX_ACTUATORS];
|
||||||
Vector3f motor_thrust_vec[12];
|
float yaw_factor[SIM_FRAME_MAX_ACTUATORS] {0,};
|
||||||
float yaw_factor[12] = {0};
|
|
||||||
|
|
||||||
// number of motors
|
// number of motors
|
||||||
float num_motors = 4;
|
float num_motors = 4;
|
||||||
|
Loading…
Reference in New Issue
Block a user