2016-04-21 06:56:44 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
multicopter simulator class
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
|
|
|
#include "SIM_Motor.h"
|
|
|
|
|
2022-04-13 18:15:57 -03:00
|
|
|
#if USE_PICOJSON
|
|
|
|
#include "picojson.h"
|
|
|
|
#endif
|
|
|
|
|
2016-05-01 18:56:56 -03:00
|
|
|
namespace SITL {
|
2016-04-21 06:56:44 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
class to describe a multicopter frame type
|
|
|
|
*/
|
|
|
|
class Frame {
|
|
|
|
public:
|
|
|
|
const char *name;
|
|
|
|
uint8_t num_motors;
|
2016-07-03 09:02:09 -03:00
|
|
|
Motor *motors;
|
2016-04-21 06:56:44 -03:00
|
|
|
|
|
|
|
Frame(const char *_name,
|
|
|
|
uint8_t _num_motors,
|
2016-07-03 09:02:09 -03:00
|
|
|
Motor *_motors) :
|
2020-10-24 17:38:02 -03:00
|
|
|
name(_name),
|
|
|
|
num_motors(_num_motors),
|
|
|
|
motors(_motors) {}
|
2016-04-21 06:56:44 -03:00
|
|
|
|
2022-04-22 13:25:41 -03:00
|
|
|
#if AP_SIM_ENABLED
|
2016-04-21 06:56:44 -03:00
|
|
|
// find a frame by name
|
|
|
|
static Frame *find_frame(const char *name);
|
|
|
|
|
|
|
|
// initialise frame
|
2020-10-24 17:38:02 -03:00
|
|
|
void init(const char *frame_str, Battery *_battery);
|
2016-04-21 06:56:44 -03:00
|
|
|
|
|
|
|
// calculate rotational and linear accelerations
|
|
|
|
void calculate_forces(const Aircraft &aircraft,
|
2018-07-31 09:33:23 -03:00
|
|
|
const struct sitl_input &input,
|
2020-10-20 04:19:54 -03:00
|
|
|
Vector3f &rot_accel, Vector3f &body_accel, float* rpm,
|
|
|
|
bool use_drag=true);
|
2022-04-22 13:25:41 -03:00
|
|
|
#endif // AP_SIM_ENABLED
|
|
|
|
|
2016-04-21 06:56:44 -03:00
|
|
|
float terminal_velocity;
|
|
|
|
float terminal_rotation_rate;
|
|
|
|
uint8_t motor_offset;
|
2019-01-12 23:07:36 -04:00
|
|
|
|
|
|
|
// calculate current and voltage
|
2020-10-20 04:19:54 -03:00
|
|
|
void current_and_voltage(float &voltage, float ¤t);
|
|
|
|
|
|
|
|
// get mass in kg
|
|
|
|
float get_mass(void) const {
|
|
|
|
return mass;
|
|
|
|
}
|
|
|
|
|
2020-10-21 01:42:36 -03:00
|
|
|
// set mass in kg
|
|
|
|
void set_mass(float new_mass) {
|
|
|
|
mass = new_mass;
|
|
|
|
}
|
|
|
|
|
2020-10-20 04:19:54 -03:00
|
|
|
private:
|
|
|
|
/*
|
|
|
|
parameters that define the multicopter model. Can be loaded from
|
|
|
|
a json file to give a custom model
|
|
|
|
*/
|
|
|
|
const struct Model {
|
|
|
|
// model mass kg
|
|
|
|
float mass = 3.0;
|
|
|
|
|
|
|
|
// diameter of model
|
|
|
|
float diagonal_size = 0.35;
|
|
|
|
|
|
|
|
/*
|
|
|
|
the ref values are for a test at fixed angle, used to estimate drag
|
|
|
|
*/
|
|
|
|
float refSpd = 15.08; // m/s
|
|
|
|
float refAngle = 45; // degrees
|
|
|
|
float refVoltage = 12.09; // Volts
|
|
|
|
float refCurrent = 29.3; // Amps
|
|
|
|
float refAlt = 593; // altitude AMSL
|
|
|
|
float refTempC = 25; // temperature C
|
|
|
|
float refBatRes = 0.01; // BAT.Res
|
|
|
|
|
|
|
|
// full pack voltage
|
|
|
|
float maxVoltage = 4.2*3;
|
|
|
|
|
2020-10-24 17:38:02 -03:00
|
|
|
// battery capacity in Ah. Use zero for unlimited
|
|
|
|
float battCapacityAh = 0.0;
|
|
|
|
|
2022-01-10 08:44:34 -04:00
|
|
|
// CTUN.ThO at hover at refAlt
|
2020-10-20 04:19:54 -03:00
|
|
|
float hoverThrOut = 0.39;
|
|
|
|
|
|
|
|
// MOT_THST_EXPO
|
|
|
|
float propExpo = 0.65;
|
|
|
|
|
|
|
|
// scaling factor for yaw response, deg/sec
|
|
|
|
float refRotRate = 120;
|
|
|
|
|
|
|
|
// MOT params are from the reference test
|
|
|
|
// MOT_PWM_MIN
|
|
|
|
float pwmMin = 1000;
|
|
|
|
// MOT_PWM_MAX
|
|
|
|
float pwmMax = 2000;
|
|
|
|
// MOT_SPIN_MIN
|
|
|
|
float spin_min = 0.15;
|
|
|
|
// MOT_SPIN_MAX
|
|
|
|
float spin_max = 0.95;
|
|
|
|
|
|
|
|
// maximum slew rate of motors
|
|
|
|
float slew_max = 150;
|
2020-11-28 18:51:58 -04:00
|
|
|
|
|
|
|
// rotor disc area in m**2 for 4 x 0.35m dia rotors
|
2022-01-10 08:44:34 -04:00
|
|
|
// Note that coaxial rotors count as one rotor only when calculating effective disc area
|
2020-11-28 18:51:58 -04:00
|
|
|
float disc_area = 0.385;
|
|
|
|
|
|
|
|
// momentum drag coefficient
|
|
|
|
float mdrag_coef = 0.2;
|
|
|
|
|
2022-04-13 11:03:53 -03:00
|
|
|
// if zero value will be estimated from mass
|
|
|
|
Vector3f moment_of_inertia;
|
|
|
|
|
2022-04-13 18:15:57 -03:00
|
|
|
// if zero will no be used
|
|
|
|
Vector3f motor_pos[12];
|
|
|
|
Vector3f motor_thrust_vec[12];
|
2022-04-20 14:52:31 -03:00
|
|
|
float yaw_factor[12] = {0};
|
2022-04-13 18:15:57 -03:00
|
|
|
|
2022-05-01 07:52:42 -03:00
|
|
|
// number of motors
|
|
|
|
float num_motors = 4;
|
|
|
|
|
2020-10-20 04:19:54 -03:00
|
|
|
} default_model;
|
|
|
|
|
2022-04-22 13:26:52 -03:00
|
|
|
protected:
|
|
|
|
#if USE_PICOJSON
|
|
|
|
// load frame parameters from a json model file
|
|
|
|
void load_frame_params(const char *model_json);
|
|
|
|
#endif
|
|
|
|
|
2022-04-30 10:13:16 -03:00
|
|
|
// get air density in kg/m^3
|
|
|
|
float get_air_density(float alt_amsl) const;
|
|
|
|
|
2020-10-20 04:19:54 -03:00
|
|
|
struct Model model;
|
|
|
|
|
2022-04-22 13:26:52 -03:00
|
|
|
private:
|
2020-10-20 04:19:54 -03:00
|
|
|
// exposed area times coefficient of drag
|
|
|
|
float areaCd;
|
|
|
|
float mass;
|
2020-10-24 17:38:02 -03:00
|
|
|
float last_param_voltage;
|
2022-04-22 13:25:41 -03:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
Battery *battery;
|
|
|
|
#endif
|
2020-10-20 04:19:54 -03:00
|
|
|
|
2022-04-22 13:26:52 -03:00
|
|
|
// json parsing helpers
|
2022-04-24 19:43:35 -03:00
|
|
|
#if USE_PICOJSON
|
2022-04-13 18:15:57 -03:00
|
|
|
void parse_float(picojson::value val, const char* label, float ¶m);
|
|
|
|
void parse_vector3(picojson::value val, const char* label, Vector3f ¶m);
|
2022-04-24 19:43:35 -03:00
|
|
|
#endif
|
2016-04-21 06:56:44 -03:00
|
|
|
};
|
2016-05-01 18:56:56 -03:00
|
|
|
}
|