2015-10-22 11:04:23 -03:00
|
|
|
#pragma once
|
2012-06-29 02:06:28 -03:00
|
|
|
|
2021-10-10 22:12:20 -03:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
2019-11-11 00:38:43 -04:00
|
|
|
|
2021-10-10 22:12:20 -03:00
|
|
|
#if AP_SIM_ENABLED
|
2019-11-11 00:38:43 -04:00
|
|
|
|
2018-05-23 02:09:57 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-10-22 10:58:33 -03:00
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2020-06-30 04:03:24 -03:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
2022-05-16 02:25:55 -03:00
|
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
2019-01-01 23:14:00 -04:00
|
|
|
#include <AP_Common/Location.h>
|
2019-12-23 03:03:30 -04:00
|
|
|
#include <AP_Compass/AP_Compass.h>
|
2021-01-08 06:50:48 -04:00
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
2019-10-07 04:30:22 -03:00
|
|
|
#include "SIM_Buzzer.h"
|
2018-07-31 09:33:23 -03:00
|
|
|
#include "SIM_Gripper_EPM.h"
|
2019-10-08 21:00:53 -03:00
|
|
|
#include "SIM_Gripper_Servo.h"
|
2020-08-03 00:24:27 -03:00
|
|
|
#include "SIM_I2C.h"
|
2021-07-12 22:37:14 -03:00
|
|
|
#include "SIM_SPI.h"
|
2019-01-08 21:39:44 -04:00
|
|
|
#include "SIM_Parachute.h"
|
2018-08-03 07:52:20 -03:00
|
|
|
#include "SIM_Precland.h"
|
2019-10-08 21:00:53 -03:00
|
|
|
#include "SIM_Sprayer.h"
|
|
|
|
#include "SIM_ToneAlarm.h"
|
2019-11-11 00:38:43 -04:00
|
|
|
#include "SIM_EFI_MegaSquirt.h"
|
2019-09-28 08:32:57 -03:00
|
|
|
#include "SIM_RichenPower.h"
|
2022-01-06 21:36:48 -04:00
|
|
|
#include "SIM_Loweheiser.h"
|
2021-06-28 19:24:15 -03:00
|
|
|
#include "SIM_FETtecOneWireESC.h"
|
2020-09-22 22:03:38 -03:00
|
|
|
#include "SIM_IntelligentEnergy24.h"
|
2020-03-17 20:07:11 -03:00
|
|
|
#include "SIM_Ship.h"
|
2021-10-16 00:10:40 -03:00
|
|
|
#include "SIM_GPS.h"
|
2023-01-22 03:35:53 -04:00
|
|
|
#include "SIM_DroneCANDevice.h"
|
2023-10-20 01:56:40 -03:00
|
|
|
#include "SIM_ADSB_Sagetech_MXS.h"
|
2018-07-31 09:33:23 -03:00
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
namespace SITL {
|
|
|
|
|
2020-02-09 23:11:40 -04:00
|
|
|
enum class LedLayout {
|
|
|
|
ROWS=0,
|
|
|
|
LUMINOUSBEE=1,
|
|
|
|
};
|
|
|
|
|
2018-12-04 00:06:53 -04:00
|
|
|
struct vector3f_array {
|
|
|
|
uint16_t length;
|
|
|
|
Vector3f *data;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct float_array {
|
|
|
|
uint16_t length;
|
|
|
|
float *data;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2015-11-22 22:25:00 -04:00
|
|
|
struct sitl_fdm {
|
|
|
|
// this is the structure passed between FDM models and the main SITL code
|
2015-05-02 07:29:16 -03:00
|
|
|
uint64_t timestamp_us;
|
2017-05-02 06:35:57 -03:00
|
|
|
Location home;
|
2015-05-04 22:49:54 -03:00
|
|
|
double latitude, longitude; // degrees
|
|
|
|
double altitude; // MSL
|
|
|
|
double heading; // degrees
|
|
|
|
double speedN, speedE, speedD; // m/s
|
|
|
|
double xAccel, yAccel, zAccel; // m/s/s in body frame
|
2021-04-24 21:33:58 -03:00
|
|
|
double rollRate, pitchRate, yawRate; // degrees/s in body frame
|
2015-05-04 22:49:54 -03:00
|
|
|
double rollDeg, pitchDeg, yawDeg; // euler angles, degrees
|
2017-04-15 08:20:28 -03:00
|
|
|
Quaternion quaternion;
|
2015-05-04 22:49:54 -03:00
|
|
|
double airspeed; // m/s
|
2020-11-24 22:44:46 -04:00
|
|
|
Vector3f velocity_air_bf; // velocity relative to airmass, body frame
|
2015-11-22 22:31:09 -04:00
|
|
|
double battery_voltage; // Volts
|
|
|
|
double battery_current; // Amps
|
2020-10-24 17:38:02 -03:00
|
|
|
double battery_remaining; // Ah, if non-zero capacity
|
2019-09-27 16:56:15 -03:00
|
|
|
uint8_t num_motors;
|
2022-08-18 04:18:32 -03:00
|
|
|
uint32_t motor_mask;
|
|
|
|
float rpm[32]; // RPM of all motors
|
2016-05-03 23:49:42 -03:00
|
|
|
uint8_t rcin_chan_count;
|
2020-07-25 13:04:49 -03:00
|
|
|
float rcin[12]; // RC input 0..1
|
2017-01-09 05:16:13 -04:00
|
|
|
double range; // rangefinder value
|
2016-06-17 00:46:12 -03:00
|
|
|
Vector3f bodyMagField; // Truth XYZ magnetic field vector in body-frame. Includes motor interference. Units are milli-Gauss.
|
2016-10-16 18:58:59 -03:00
|
|
|
Vector3f angAccel; // Angular acceleration in degrees/s/s about the XYZ body axes
|
2018-12-04 00:06:53 -04:00
|
|
|
|
|
|
|
struct {
|
|
|
|
// data from simulated laser scanner, if available
|
|
|
|
struct vector3f_array points;
|
|
|
|
struct float_array ranges;
|
|
|
|
} scanner;
|
2020-07-17 20:37:51 -03:00
|
|
|
|
2022-10-02 05:21:54 -03:00
|
|
|
#define SITL_NUM_RANGEFINDERS 10
|
|
|
|
float rangefinder_m[SITL_NUM_RANGEFINDERS];
|
2022-05-16 02:25:55 -03:00
|
|
|
float airspeed_raw_pressure[AIRSPEED_MAX_SENSORS];
|
2020-08-15 12:35:50 -03:00
|
|
|
|
|
|
|
struct {
|
|
|
|
float speed;
|
|
|
|
float direction;
|
|
|
|
} wind_vane_apparent;
|
2021-05-17 21:25:12 -03:00
|
|
|
|
|
|
|
bool is_lock_step_scheduled;
|
2022-07-29 22:45:27 -03:00
|
|
|
|
|
|
|
// earthframe wind, from backends that know it
|
|
|
|
Vector3f wind_ef;
|
2024-01-07 22:07:46 -04:00
|
|
|
|
|
|
|
// AGL altitude, usually derived from the terrain database in simulation:
|
|
|
|
float height_agl;
|
|
|
|
|
2012-06-29 02:06:28 -03:00
|
|
|
};
|
|
|
|
|
2015-06-29 19:54:46 -03:00
|
|
|
// number of rc output channels
|
2022-01-02 18:54:46 -04:00
|
|
|
#define SITL_NUM_CHANNELS 32
|
2015-06-29 19:54:46 -03:00
|
|
|
|
2021-07-30 07:17:35 -03:00
|
|
|
class SIM {
|
2012-06-29 02:06:28 -03:00
|
|
|
public:
|
2015-05-04 22:49:54 -03:00
|
|
|
|
2021-07-30 07:17:35 -03:00
|
|
|
SIM() {
|
2015-05-04 22:49:54 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
2017-04-12 03:28:04 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_info2);
|
2020-01-26 00:16:46 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_info3);
|
2021-10-10 22:12:20 -03:00
|
|
|
#if HAL_SIM_GPS_ENABLED
|
2020-06-30 04:09:50 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_gps);
|
2021-10-10 22:12:20 -03:00
|
|
|
#endif
|
2020-06-30 04:09:50 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_mag);
|
2021-01-08 06:50:48 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_ins);
|
2020-11-12 17:12:36 -04:00
|
|
|
#ifdef SFML_JOYSTICK
|
|
|
|
AP_Param::setup_object_defaults(this, var_sfml_joystick);
|
|
|
|
#endif // SFML_JOYSTICK
|
2020-11-24 21:27:56 -04:00
|
|
|
for (uint8_t i=0; i<BARO_MAX_INSTANCES; i++) {
|
|
|
|
AP_Param::setup_object_defaults(&baro[i], baro[i].var_info);
|
|
|
|
}
|
2022-05-16 02:25:55 -03:00
|
|
|
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
|
|
|
|
AP_Param::setup_object_defaults(&airspeed[i], airspeed[i].var_info);
|
|
|
|
}
|
2022-07-27 14:23:44 -03:00
|
|
|
// set compass offset
|
|
|
|
for (uint8_t i = 0; i < HAL_COMPASS_MAX_SENSORS; i++) {
|
|
|
|
mag_ofs[i].set(Vector3f(5, 13, -18));
|
|
|
|
}
|
2019-02-10 01:01:19 -04:00
|
|
|
if (_singleton != nullptr) {
|
2018-05-02 08:30:59 -03:00
|
|
|
AP_HAL::panic("Too many SITL instances");
|
|
|
|
}
|
2019-02-10 01:01:19 -04:00
|
|
|
_singleton = this;
|
2012-12-12 17:48:38 -04:00
|
|
|
}
|
|
|
|
|
2018-05-02 08:30:59 -03:00
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(SIM);
|
2018-05-02 08:30:59 -03:00
|
|
|
|
2021-07-30 07:17:35 -03:00
|
|
|
static SIM *_singleton;
|
|
|
|
static SIM *get_singleton() { return _singleton; }
|
2018-05-02 08:30:59 -03:00
|
|
|
|
2018-07-31 07:24:10 -03:00
|
|
|
enum SITL_RCFail {
|
|
|
|
SITL_RCFail_None = 0,
|
|
|
|
SITL_RCFail_NoPulses = 1,
|
|
|
|
SITL_RCFail_Throttle950 = 2,
|
|
|
|
};
|
|
|
|
|
2020-07-07 10:17:08 -03:00
|
|
|
enum GPSHeading {
|
|
|
|
GPS_HEADING_NONE = 0,
|
|
|
|
GPS_HEADING_HDT = 1,
|
|
|
|
GPS_HEADING_THS = 2,
|
2021-10-23 06:42:04 -03:00
|
|
|
GPS_HEADING_KSXT = 3,
|
2020-07-07 10:17:08 -03:00
|
|
|
};
|
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
struct sitl_fdm state;
|
|
|
|
|
2019-12-24 17:18:30 -04:00
|
|
|
// throttle when motors are active
|
|
|
|
float throttle;
|
2015-11-16 00:10:29 -04:00
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2017-04-12 03:28:04 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info2[];
|
2020-01-26 00:16:46 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_info3[];
|
2021-10-10 22:12:20 -03:00
|
|
|
#if HAL_SIM_GPS_ENABLED
|
2020-06-30 04:09:50 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_gps[];
|
2021-10-10 22:12:20 -03:00
|
|
|
#endif
|
2020-06-30 04:09:50 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_mag[];
|
2021-01-08 06:50:48 -04:00
|
|
|
static const struct AP_Param::GroupInfo var_ins[];
|
2020-11-12 17:12:36 -04:00
|
|
|
#ifdef SFML_JOYSTICK
|
|
|
|
static const struct AP_Param::GroupInfo var_sfml_joystick[];
|
|
|
|
#endif //SFML_JOYSTICK
|
2015-05-04 22:49:54 -03:00
|
|
|
|
2020-01-13 13:47:52 -04:00
|
|
|
// Board Orientation (and inverse)
|
|
|
|
Matrix3f ahrs_rotation;
|
|
|
|
Matrix3f ahrs_rotation_inv;
|
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
AP_Float mag_noise; // in mag units (earth field is 818)
|
|
|
|
AP_Vector3f mag_mot; // in mag units per amp
|
2020-05-12 15:07:42 -03:00
|
|
|
AP_Vector3f mag_ofs[HAL_COMPASS_MAX_SENSORS]; // in mag units
|
|
|
|
AP_Vector3f mag_diag[HAL_COMPASS_MAX_SENSORS]; // diagonal corrections
|
|
|
|
AP_Vector3f mag_offdiag[HAL_COMPASS_MAX_SENSORS]; // off-diagonal corrections
|
|
|
|
AP_Int8 mag_orient[HAL_COMPASS_MAX_SENSORS]; // external compass orientation
|
2020-08-27 23:26:42 -03:00
|
|
|
AP_Int8 mag_fail[HAL_COMPASS_MAX_SENSORS]; // fail magnetometer, 1 for no data, 2 for freeze
|
2023-09-20 19:57:39 -03:00
|
|
|
AP_Int8 mag_save_ids;
|
2016-10-25 05:54:56 -03:00
|
|
|
AP_Float servo_speed; // servo speed in seconds
|
2012-06-29 02:06:28 -03:00
|
|
|
|
2022-01-10 08:44:34 -04:00
|
|
|
AP_Float sonar_glitch;// probability between 0-1 that any given sonar sample will read as max distance
|
2013-11-26 01:58:30 -04:00
|
|
|
AP_Float sonar_noise; // in metres
|
2014-08-10 09:36:38 -03:00
|
|
|
AP_Float sonar_scale; // meters per volt
|
2022-04-18 02:30:09 -03:00
|
|
|
AP_Int8 sonar_rot; // from rotations enumeration
|
2013-11-26 01:42:43 -04:00
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
AP_Float drift_speed; // degrees/second/minute
|
|
|
|
AP_Float drift_time; // period in minutes
|
2012-08-17 01:21:43 -03:00
|
|
|
AP_Float engine_mul; // engine multiplier
|
2017-03-20 17:32:54 -03:00
|
|
|
AP_Int8 engine_fail; // engine servo to fail (0-7)
|
2020-07-07 20:52:38 -03:00
|
|
|
|
|
|
|
AP_Float gps_noise[2]; // amplitude of the gps altitude error
|
|
|
|
AP_Int16 gps_lock_time[2]; // delay in seconds before GPS gets lock
|
|
|
|
AP_Int16 gps_alt_offset[2]; // gps alt error
|
|
|
|
AP_Int8 gps_disable[2]; // disable simulated GPS
|
2022-01-05 20:32:55 -04:00
|
|
|
AP_Int16 gps_delay_ms[2]; // delay in milliseconds
|
2021-10-16 00:10:40 -03:00
|
|
|
AP_Int8 gps_type[2]; // see enum SITL::GPS::Type
|
2020-07-07 20:52:38 -03:00
|
|
|
AP_Float gps_byteloss[2];// byte loss as a percent
|
|
|
|
AP_Int8 gps_numsats[2]; // number of visible satellites
|
2020-01-26 00:16:46 -04:00
|
|
|
AP_Vector3f gps_glitch[2]; // glitch offsets in lat, lon and altitude
|
2020-07-07 20:52:38 -03:00
|
|
|
AP_Int8 gps_hertz[2]; // GPS update rate in Hz
|
|
|
|
AP_Int8 gps_hdg_enabled[2]; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED
|
2020-07-16 07:17:54 -03:00
|
|
|
AP_Float gps_drift_alt[2]; // altitude drift error
|
2020-07-07 20:52:38 -03:00
|
|
|
AP_Vector3f gps_pos_offset[2]; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
|
2020-08-20 07:41:27 -03:00
|
|
|
AP_Float gps_accuracy[2];
|
2020-07-16 07:17:54 -03:00
|
|
|
AP_Vector3f gps_vel_err[2]; // Velocity error offsets in NED (x = N, y = E, z = D)
|
2023-12-01 03:29:39 -04:00
|
|
|
AP_Int8 gps_jam[2]; // jamming simulation enable
|
2020-07-07 20:52:38 -03:00
|
|
|
|
2021-06-17 22:03:56 -03:00
|
|
|
// initial offset on GPS lat/lon, used to shift origin
|
|
|
|
AP_Float gps_init_lat_ofs;
|
|
|
|
AP_Float gps_init_lon_ofs;
|
|
|
|
AP_Float gps_init_alt_ofs;
|
|
|
|
|
2022-12-18 17:01:41 -04:00
|
|
|
// log number for GPS::update_file()
|
|
|
|
AP_Int16 gps_log_num;
|
|
|
|
|
2013-10-02 05:44:20 -03:00
|
|
|
AP_Float batt_voltage; // battery voltage base
|
2020-10-24 17:38:02 -03:00
|
|
|
AP_Float batt_capacity_ah; // battery capacity in Ah
|
2015-05-04 22:49:54 -03:00
|
|
|
AP_Int8 rc_fail; // fail RC input
|
2018-07-23 23:46:11 -03:00
|
|
|
AP_Int8 rc_chancount; // channel count
|
2014-04-21 02:24:45 -03:00
|
|
|
AP_Int8 float_exception; // enable floating point exception checks
|
2023-08-19 19:49:50 -03:00
|
|
|
AP_Int32 can_servo_mask; // mask of servos/escs coming from CAN
|
2023-08-25 22:29:38 -03:00
|
|
|
|
|
|
|
#if HAL_NUM_CAN_IFACES
|
|
|
|
enum class CANTransport : uint8_t {
|
|
|
|
MulticastUDP = 0,
|
|
|
|
SocketCAN = 1
|
|
|
|
};
|
|
|
|
AP_Enum<CANTransport> can_transport[HAL_NUM_CAN_IFACES];
|
|
|
|
#endif
|
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
AP_Int8 flow_enable; // enable simulated optflow
|
|
|
|
AP_Int16 flow_rate; // optflow data rate (Hz)
|
|
|
|
AP_Int8 flow_delay; // optflow data delay
|
|
|
|
AP_Int8 terrain_enable; // enable using terrain for height
|
2018-04-18 00:34:17 -03:00
|
|
|
AP_Int16 pin_mask; // for GPIO emulation
|
2016-09-18 18:45:24 -03:00
|
|
|
AP_Float speedup; // simulation speedup
|
2022-01-10 08:44:34 -04:00
|
|
|
AP_Int8 odom_enable; // enable visual odometry data
|
2019-01-24 20:26:19 -04:00
|
|
|
AP_Int8 telem_baudlimit_enable; // enable baudrate limiting on links
|
2019-02-14 05:23:25 -04:00
|
|
|
AP_Float flow_noise; // optical flow measurement noise (rad/sec)
|
2019-01-05 06:45:02 -04:00
|
|
|
AP_Int8 baro_count; // number of simulated baros to create
|
2020-08-27 05:32:37 -03:00
|
|
|
AP_Int8 imu_count; // number of simulated IMUs to create
|
2019-09-17 05:10:06 -03:00
|
|
|
AP_Int32 loop_delay; // extra delay to add to every loop
|
2020-08-27 23:26:42 -03:00
|
|
|
AP_Float mag_scaling[MAX_CONNECTED_MAGS]; // scaling factor
|
2019-12-23 03:03:30 -04:00
|
|
|
AP_Int32 mag_devid[MAX_CONNECTED_MAGS]; // Mag devid
|
2020-04-13 12:39:27 -03:00
|
|
|
AP_Float buoyancy; // submarine buoyancy in Newtons
|
2020-06-03 01:34:23 -03:00
|
|
|
AP_Int16 loop_rate_hz;
|
2022-12-05 00:06:18 -04:00
|
|
|
AP_Int16 loop_time_jitter_us;
|
2022-05-23 02:11:07 -03:00
|
|
|
AP_Int32 on_hardware_output_enable_mask; // mask of output channels passed through to actual hardware
|
2023-09-04 11:46:21 -03:00
|
|
|
AP_Int16 on_hardware_relay_enable_mask; // mask of relays passed through to actual hardware
|
2018-07-31 09:33:23 -03:00
|
|
|
|
2023-01-15 00:55:38 -04:00
|
|
|
AP_Float uart_byte_loss_pct;
|
|
|
|
|
2020-11-12 17:12:36 -04:00
|
|
|
#ifdef SFML_JOYSTICK
|
|
|
|
AP_Int8 sfml_joystick_id;
|
|
|
|
AP_Int8 sfml_joystick_axis[8];
|
|
|
|
#endif
|
|
|
|
|
2020-11-24 21:27:56 -04:00
|
|
|
// baro parameters
|
|
|
|
class BaroParm {
|
|
|
|
public:
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
AP_Float noise; // in metres
|
|
|
|
AP_Float drift; // in metres per second
|
|
|
|
AP_Float glitch; // glitch in meters
|
|
|
|
AP_Int8 freeze; // freeze baro to last recorded altitude
|
|
|
|
AP_Int8 disable; // disable simulated barometers
|
|
|
|
AP_Int16 delay; // barometer data delay in ms
|
2020-11-24 22:44:46 -04:00
|
|
|
|
|
|
|
// wind coefficients
|
|
|
|
AP_Float wcof_xp;
|
|
|
|
AP_Float wcof_xn;
|
|
|
|
AP_Float wcof_yp;
|
|
|
|
AP_Float wcof_yn;
|
2022-11-22 16:59:05 -04:00
|
|
|
AP_Float wcof_zp;
|
|
|
|
AP_Float wcof_zn;
|
2020-11-24 21:27:56 -04:00
|
|
|
};
|
|
|
|
BaroParm baro[BARO_MAX_INSTANCES];
|
|
|
|
|
2022-05-16 02:25:55 -03:00
|
|
|
// airspeed parameters
|
|
|
|
class AirspeedParm {
|
|
|
|
public:
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
AP_Float noise; // pressure noise
|
|
|
|
AP_Float fail; // airspeed value in m/s to fail to
|
|
|
|
AP_Float fail_pressure; // pitot tube failure pressure in Pa
|
|
|
|
AP_Float fail_pitot_pressure; // pitot tube failure pressure in Pa
|
|
|
|
AP_Float offset; // airspeed sensor offset in m/s
|
|
|
|
AP_Float ratio; // airspeed ratios
|
|
|
|
AP_Int8 signflip;
|
|
|
|
};
|
|
|
|
AirspeedParm airspeed[AIRSPEED_MAX_SENSORS];
|
|
|
|
|
2019-11-11 00:38:43 -04:00
|
|
|
// EFI type
|
|
|
|
enum EFIType {
|
|
|
|
EFI_TYPE_NONE = 0,
|
|
|
|
EFI_TYPE_MS = 1,
|
2022-01-06 21:36:48 -04:00
|
|
|
EFI_TYPE_LOWEHEISER = 2,
|
2023-11-08 23:56:36 -04:00
|
|
|
EFI_TYPE_HIRTH = 8,
|
2019-11-11 00:38:43 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
AP_Int8 efi_type;
|
|
|
|
|
2012-08-24 08:22:20 -03:00
|
|
|
// wind control
|
2018-04-30 12:25:19 -03:00
|
|
|
enum WindType {
|
|
|
|
WIND_TYPE_SQRT = 0,
|
|
|
|
WIND_TYPE_NO_LIMIT = 1,
|
|
|
|
WIND_TYPE_COEF = 2,
|
|
|
|
};
|
|
|
|
|
2016-07-15 22:36:59 -03:00
|
|
|
float wind_speed_active;
|
|
|
|
float wind_direction_active;
|
2018-01-30 12:38:36 -04:00
|
|
|
float wind_dir_z_active;
|
2012-08-24 08:22:20 -03:00
|
|
|
AP_Float wind_speed;
|
|
|
|
AP_Float wind_direction;
|
|
|
|
AP_Float wind_turbulance;
|
2018-01-30 12:38:36 -04:00
|
|
|
AP_Float wind_dir_z;
|
2018-04-30 12:25:19 -03:00
|
|
|
AP_Int8 wind_type; // enum WindLimitType
|
|
|
|
AP_Float wind_type_alt;
|
|
|
|
AP_Float wind_type_coef;
|
2015-04-13 03:22:57 -03:00
|
|
|
|
|
|
|
AP_Int16 mag_delay; // magnetometer data delay in ms
|
|
|
|
|
2016-06-15 00:47:19 -03:00
|
|
|
// ADSB related run-time options
|
2023-10-20 01:56:40 -03:00
|
|
|
enum class ADSBType {
|
|
|
|
Shortcut = 0,
|
|
|
|
SageTechMXS = 3,
|
|
|
|
};
|
|
|
|
AP_Enum<ADSBType> adsb_types; // bitmask of active ADSB types
|
2016-06-15 00:47:19 -03:00
|
|
|
AP_Int16 adsb_plane_count;
|
|
|
|
AP_Float adsb_radius_m;
|
|
|
|
AP_Float adsb_altitude_m;
|
2016-08-16 18:16:03 -03:00
|
|
|
AP_Int8 adsb_tx;
|
2016-06-15 00:47:19 -03:00
|
|
|
|
2016-06-17 00:46:12 -03:00
|
|
|
// Earth magnetic field anomaly
|
|
|
|
AP_Vector3f mag_anomaly_ned; // NED anomaly vector at ground level (mGauss)
|
|
|
|
AP_Float mag_anomaly_hgt; // height above ground where anomally strength has decayed to 1/8 of the ground level value (m)
|
|
|
|
|
2016-10-14 20:42:45 -03:00
|
|
|
// Body frame sensor position offsets
|
|
|
|
AP_Vector3f imu_pos_offset; // XYZ position of the IMU accelerometer relative to the body frame origin (m)
|
|
|
|
AP_Vector3f rngfnd_pos_offset; // XYZ position of the range finder zero range datum relative to the body frame origin (m)
|
|
|
|
AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
|
2020-04-13 03:04:26 -03:00
|
|
|
AP_Vector3f vicon_pos_offset; // XYZ position of the vicon sensor relative to the body frame origin (m)
|
2016-10-14 20:42:45 -03:00
|
|
|
|
2021-08-16 03:55:14 -03:00
|
|
|
// barometer temperature control
|
|
|
|
AP_Float temp_start; // [deg C] Barometer start temperature
|
|
|
|
AP_Float temp_board_offset; // [deg C] Barometer board temperature offset from atmospheric temperature
|
|
|
|
AP_Float temp_tconst; // [deg C] Barometer warmup temperature time constant
|
2017-04-12 19:48:50 -03:00
|
|
|
AP_Float temp_baro_factor;
|
2017-04-12 03:28:04 -03:00
|
|
|
|
2019-05-26 06:56:10 -03:00
|
|
|
AP_Int8 thermal_scenario;
|
|
|
|
|
2018-11-08 23:06:30 -04:00
|
|
|
// weight on wheels pin
|
|
|
|
AP_Int8 wow_pin;
|
2019-01-07 05:32:17 -04:00
|
|
|
|
|
|
|
// vibration frequencies in Hz on each axis
|
|
|
|
AP_Vector3f vibe_freq;
|
2017-11-27 06:45:23 -04:00
|
|
|
|
2019-12-24 17:18:30 -04:00
|
|
|
// max frequency to use as baseline for adding motor noise for the gyros and accels
|
2019-09-27 16:56:15 -03:00
|
|
|
AP_Float vibe_motor;
|
2020-01-28 18:25:49 -04:00
|
|
|
// amplitude scaling of motor noise relative to gyro/accel noise
|
|
|
|
AP_Float vibe_motor_scale;
|
2022-07-03 04:40:12 -03:00
|
|
|
|
|
|
|
// what harmonics to generate
|
|
|
|
AP_Int16 vibe_motor_harmonics;
|
|
|
|
|
2022-08-18 06:00:36 -03:00
|
|
|
// what servos are motors
|
|
|
|
AP_Int32 vibe_motor_mask;
|
|
|
|
|
2019-12-24 17:18:30 -04:00
|
|
|
// minimum throttle for addition of ins noise
|
|
|
|
AP_Float ins_noise_throttle_min;
|
2019-09-27 16:56:15 -03:00
|
|
|
|
2017-11-27 06:45:23 -04:00
|
|
|
struct {
|
|
|
|
AP_Float x;
|
|
|
|
AP_Float y;
|
|
|
|
AP_Float z;
|
|
|
|
AP_Int32 t;
|
|
|
|
|
|
|
|
uint32_t start_ms;
|
|
|
|
} shove;
|
|
|
|
|
2019-04-10 22:55:04 -03:00
|
|
|
struct {
|
|
|
|
AP_Float x;
|
|
|
|
AP_Float y;
|
|
|
|
AP_Float z;
|
|
|
|
AP_Int32 t;
|
|
|
|
|
|
|
|
uint32_t start_ms;
|
|
|
|
} twist;
|
|
|
|
|
|
|
|
AP_Int8 gnd_behav;
|
|
|
|
|
2019-05-19 12:03:16 -03:00
|
|
|
struct {
|
|
|
|
AP_Int8 enable; // 0: disabled, 1: roll and pitch, 2: roll, pitch and heave
|
|
|
|
AP_Float length; // m
|
|
|
|
AP_Float amp; // m
|
|
|
|
AP_Float direction; // deg (direction wave is coming from)
|
|
|
|
AP_Float speed; // m/s
|
|
|
|
} wave;
|
|
|
|
|
2019-05-27 20:52:11 -03:00
|
|
|
struct {
|
|
|
|
AP_Float direction; // deg (direction tide is coming from)
|
|
|
|
AP_Float speed; // m/s
|
|
|
|
} tide;
|
|
|
|
|
2019-08-15 03:53:35 -03:00
|
|
|
// original simulated position
|
|
|
|
struct {
|
|
|
|
AP_Float lat;
|
|
|
|
AP_Float lng;
|
|
|
|
AP_Float alt; // metres
|
|
|
|
AP_Float hdg; // 0 to 360
|
|
|
|
} opos;
|
|
|
|
|
2016-11-17 14:05:04 -04:00
|
|
|
uint16_t irlock_port;
|
2024-03-14 03:04:32 -03:00
|
|
|
uint16_t rcin_port;
|
2016-11-17 14:05:04 -04:00
|
|
|
|
2020-09-04 19:23:51 -03:00
|
|
|
time_t start_time_UTC;
|
|
|
|
|
2021-02-01 12:37:57 -04:00
|
|
|
void simstate_send(mavlink_channel_t chan) const;
|
|
|
|
void sim_state_send(mavlink_channel_t chan) const;
|
2012-06-29 02:06:28 -03:00
|
|
|
|
2019-01-17 18:15:50 -04:00
|
|
|
void Log_Write_SIMSTATE();
|
2014-01-03 01:01:18 -04:00
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
// convert a set of roll rates from earth frame to body frame
|
|
|
|
static void convert_body_frame(double rollDeg, double pitchDeg,
|
|
|
|
double rollRate, double pitchRate, double yawRate,
|
|
|
|
double *p, double *q, double *r);
|
2015-05-02 07:29:16 -03:00
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
// convert a set of roll rates from body frame to earth frame
|
2015-05-02 07:29:16 -03:00
|
|
|
static Vector3f convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro);
|
2018-07-31 09:33:23 -03:00
|
|
|
|
2020-08-03 00:24:27 -03:00
|
|
|
int i2c_ioctl(uint8_t i2c_operation, void *data) {
|
|
|
|
return i2c_sim.ioctl(i2c_operation, data);
|
|
|
|
}
|
|
|
|
|
2021-07-12 22:37:14 -03:00
|
|
|
int spi_ioctl(uint8_t bus, uint8_t cs_pin, uint8_t spi_operation, void *data) {
|
|
|
|
return spi_sim.ioctl(bus, cs_pin, spi_operation, data);
|
|
|
|
}
|
|
|
|
|
2018-07-31 09:33:23 -03:00
|
|
|
Sprayer sprayer_sim;
|
|
|
|
|
2020-03-17 20:07:11 -03:00
|
|
|
// simulated ship takeoffs
|
2021-10-11 02:05:28 -03:00
|
|
|
#if AP_SIM_SHIP_ENABLED
|
2020-03-17 20:07:11 -03:00
|
|
|
ShipSim shipsim;
|
2021-10-11 02:05:28 -03:00
|
|
|
#endif
|
2020-03-17 20:07:11 -03:00
|
|
|
|
2018-07-31 09:33:23 -03:00
|
|
|
Gripper_Servo gripper_sim;
|
|
|
|
Gripper_EPM gripper_epm_sim;
|
2019-01-08 21:39:44 -04:00
|
|
|
|
|
|
|
Parachute parachute_sim;
|
2019-10-07 04:30:22 -03:00
|
|
|
Buzzer buzzer_sim;
|
2020-08-03 00:24:27 -03:00
|
|
|
I2C i2c_sim;
|
2021-07-12 22:37:14 -03:00
|
|
|
SPI spi_sim;
|
2019-10-08 21:00:53 -03:00
|
|
|
ToneAlarm tonealarm_sim;
|
2018-08-03 07:52:20 -03:00
|
|
|
SIM_Precland precland_sim;
|
2019-09-28 08:32:57 -03:00
|
|
|
RichenPower richenpower_sim;
|
2022-01-06 21:36:48 -04:00
|
|
|
#if AP_SIM_LOWEHEISER_ENABLED
|
|
|
|
Loweheiser loweheiser_sim;
|
|
|
|
#endif
|
2020-09-22 22:03:38 -03:00
|
|
|
IntelligentEnergy24 ie24_sim;
|
2021-06-28 19:24:15 -03:00
|
|
|
FETtecOneWireESC fetteconewireesc_sim;
|
2023-01-22 03:35:53 -04:00
|
|
|
#if AP_TEST_DRONECAN_DRIVERS
|
|
|
|
DroneCANDevice dronecan_sim;
|
|
|
|
#endif
|
2019-10-30 07:11:52 -03:00
|
|
|
|
2021-03-06 16:58:29 -04:00
|
|
|
// ESC telemetry
|
|
|
|
AP_Int8 esc_telem;
|
2022-05-26 09:59:05 -03:00
|
|
|
// RPM when motors are armed
|
|
|
|
AP_Float esc_rpm_armed;
|
2021-03-06 16:58:29 -04:00
|
|
|
|
2019-10-30 07:11:52 -03:00
|
|
|
struct {
|
|
|
|
// LED state, for serial LED emulation
|
|
|
|
struct {
|
|
|
|
uint8_t rgb[3];
|
|
|
|
} rgb[16][32];
|
|
|
|
uint8_t num_leds[16];
|
|
|
|
uint32_t send_counter;
|
|
|
|
} led;
|
2019-11-11 00:38:43 -04:00
|
|
|
|
2020-02-09 23:11:40 -04:00
|
|
|
AP_Int8 led_layout;
|
2020-04-23 08:25:34 -03:00
|
|
|
|
|
|
|
// vicon parameters
|
|
|
|
AP_Vector3f vicon_glitch; // glitch in meters in vicon's local NED frame
|
|
|
|
AP_Int8 vicon_fail; // trigger vicon failure
|
|
|
|
AP_Int16 vicon_yaw; // vicon local yaw in degrees
|
2020-05-13 01:09:09 -03:00
|
|
|
AP_Int16 vicon_yaw_error; // vicon yaw error in degrees (added to reported yaw sent to vehicle)
|
2020-05-14 23:14:00 -03:00
|
|
|
AP_Int8 vicon_type_mask; // vicon message type mask (bit0:vision position estimate, bit1:vision speed estimate, bit2:vicon position estimate)
|
|
|
|
AP_Vector3f vicon_vel_glitch; // velocity glitch in m/s in vicon's local frame
|
2020-07-17 20:37:51 -03:00
|
|
|
|
|
|
|
// get the rangefinder reading for the desired instance, returns -1 for no data
|
|
|
|
float get_rangefinder(uint8_t instance);
|
|
|
|
|
2022-04-18 02:30:09 -03:00
|
|
|
float measure_distance_at_angle_bf(const Location &location, float angle) const;
|
|
|
|
|
2020-08-15 12:35:50 -03:00
|
|
|
// get the apparent wind speed and direction as set by external physics backend
|
2021-02-01 12:37:57 -04:00
|
|
|
float get_apparent_wind_dir() const{return state.wind_vane_apparent.direction;}
|
|
|
|
float get_apparent_wind_spd() const{return state.wind_vane_apparent.speed;}
|
2021-01-08 06:50:48 -04:00
|
|
|
|
2022-01-28 07:25:37 -04:00
|
|
|
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
2021-01-08 06:50:48 -04:00
|
|
|
// IMU temperature calibration params
|
|
|
|
AP_Float imu_temp_start;
|
|
|
|
AP_Float imu_temp_end;
|
|
|
|
AP_Float imu_temp_tconst;
|
|
|
|
AP_Float imu_temp_fixed;
|
2023-03-04 18:09:42 -04:00
|
|
|
AP_InertialSensor_TCal imu_tcal[INS_MAX_INSTANCES];
|
2022-01-28 07:25:37 -04:00
|
|
|
#endif
|
2021-01-19 20:53:58 -04:00
|
|
|
|
|
|
|
// IMU control parameters
|
|
|
|
AP_Float gyro_noise[INS_MAX_INSTANCES]; // in degrees/second
|
|
|
|
AP_Vector3f gyro_scale[INS_MAX_INSTANCES]; // percentage
|
2023-02-20 18:16:41 -04:00
|
|
|
AP_Vector3f gyro_bias[INS_MAX_INSTANCES]; // in rad/s
|
2021-01-19 20:53:58 -04:00
|
|
|
AP_Float accel_noise[INS_MAX_INSTANCES]; // in m/s/s
|
|
|
|
AP_Vector3f accel_bias[INS_MAX_INSTANCES]; // in m/s/s
|
2021-01-19 22:35:13 -04:00
|
|
|
AP_Vector3f accel_scale[INS_MAX_INSTANCES]; // in m/s/s
|
2021-01-24 01:54:42 -04:00
|
|
|
AP_Vector3f accel_trim;
|
2021-01-19 20:53:58 -04:00
|
|
|
AP_Float accel_fail[INS_MAX_INSTANCES]; // accelerometer failure value
|
|
|
|
// gyro and accel fail masks
|
|
|
|
AP_Int8 gyro_fail_mask;
|
|
|
|
AP_Int8 accel_fail_mask;
|
|
|
|
|
2021-04-27 14:07:43 -03:00
|
|
|
// Sailboat sim only
|
|
|
|
AP_Int8 sail_type;
|
|
|
|
|
2021-04-24 21:33:30 -03:00
|
|
|
// Master instance to use servos from with slave instances
|
|
|
|
AP_Int8 ride_along_master;
|
2022-10-14 09:04:56 -03:00
|
|
|
|
|
|
|
#if AP_SIM_INS_FILE_ENABLED
|
|
|
|
enum INSFileMode {
|
|
|
|
INS_FILE_NONE = 0,
|
|
|
|
INS_FILE_READ = 1,
|
|
|
|
INS_FILE_WRITE = 2,
|
|
|
|
INS_FILE_READ_STOP_ON_EOF = 3,
|
|
|
|
};
|
|
|
|
AP_Int8 gyro_file_rw;
|
|
|
|
AP_Int8 accel_file_rw;
|
|
|
|
#endif
|
2012-06-29 02:06:28 -03:00
|
|
|
};
|
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
} // namespace SITL
|
2018-05-02 08:30:59 -03:00
|
|
|
|
|
|
|
|
|
|
|
namespace AP {
|
2021-07-30 07:17:35 -03:00
|
|
|
SITL::SIM *sitl();
|
2018-05-02 08:30:59 -03:00
|
|
|
};
|
2019-11-11 00:38:43 -04:00
|
|
|
|
2021-10-10 22:12:20 -03:00
|
|
|
#endif // AP_SIM_ENABLED
|