2016-02-17 21:25:28 -04:00
|
|
|
#pragma once
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2020-09-12 16:04:38 -03:00
|
|
|
#if defined(HAL_BUILD_AP_PERIPH)
|
|
|
|
#include "SITL_Periph_State.h"
|
|
|
|
#else
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_SITL.h"
|
2015-05-04 03:15:12 -03:00
|
|
|
#include "AP_HAL_SITL_Namespace.h"
|
|
|
|
#include "HAL_SITL_Class.h"
|
2016-01-03 17:22:02 -04:00
|
|
|
#include "RCInput.h"
|
2012-12-14 21:54:26 -04:00
|
|
|
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/socket.h>
|
|
|
|
#include <netinet/in.h>
|
|
|
|
#include <netinet/udp.h>
|
|
|
|
#include <arpa/inet.h>
|
2020-08-23 03:24:22 -03:00
|
|
|
#include <vector>
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-08-15 19:51:46 -03:00
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
2016-03-10 20:41:18 -04:00
|
|
|
#include <AP_Compass/AP_Compass.h>
|
2015-08-15 19:51:46 -03:00
|
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
|
|
#include <SITL/SITL.h>
|
2018-07-31 09:32:43 -03:00
|
|
|
#include <SITL/SITL_Input.h>
|
2015-08-15 19:51:46 -03:00
|
|
|
#include <SITL/SIM_Gimbal.h>
|
2015-11-18 21:22:47 -04:00
|
|
|
#include <SITL/SIM_ADSB.h>
|
2018-03-07 21:25:34 -04:00
|
|
|
#include <SITL/SIM_Vicon.h>
|
2019-10-28 23:53:01 -03:00
|
|
|
#include <SITL/SIM_RF_Benewake_TF02.h>
|
|
|
|
#include <SITL/SIM_RF_Benewake_TF03.h>
|
|
|
|
#include <SITL/SIM_RF_Benewake_TFmini.h>
|
2022-08-01 20:44:01 -03:00
|
|
|
#include <SITL/SIM_RF_TeraRanger_Serial.h>
|
2019-10-28 23:53:01 -03:00
|
|
|
#include <SITL/SIM_RF_LightWareSerial.h>
|
2020-06-30 08:10:28 -03:00
|
|
|
#include <SITL/SIM_RF_LightWareSerialBinary.h>
|
2019-10-28 23:53:01 -03:00
|
|
|
#include <SITL/SIM_RF_Lanbao.h>
|
|
|
|
#include <SITL/SIM_RF_BLping.h>
|
|
|
|
#include <SITL/SIM_RF_LeddarOne.h>
|
2021-10-25 18:41:10 -03:00
|
|
|
#include <SITL/SIM_RF_USD1_v0.h>
|
|
|
|
#include <SITL/SIM_RF_USD1_v1.h>
|
2019-10-28 23:53:01 -03:00
|
|
|
#include <SITL/SIM_RF_MaxsonarSerialLV.h>
|
|
|
|
#include <SITL/SIM_RF_Wasp.h>
|
|
|
|
#include <SITL/SIM_RF_NMEA.h>
|
2020-04-21 00:29:11 -03:00
|
|
|
#include <SITL/SIM_RF_MAVLink.h>
|
2020-06-14 20:36:08 -03:00
|
|
|
#include <SITL/SIM_RF_GYUS42v2.h>
|
2020-12-29 06:30:34 -04:00
|
|
|
#include <SITL/SIM_VectorNav.h>
|
2021-09-23 19:26:03 -03:00
|
|
|
#include <SITL/SIM_LORD.h>
|
2021-04-11 11:42:17 -03:00
|
|
|
#include <SITL/SIM_AIS.h>
|
2021-10-16 00:10:40 -03:00
|
|
|
#include <SITL/SIM_GPS.h>
|
2019-12-16 22:21:13 -04:00
|
|
|
|
|
|
|
#include <SITL/SIM_Frsky_D.h>
|
2020-06-04 14:59:30 -03:00
|
|
|
#include <SITL/SIM_CRSF.h>
|
2019-12-16 22:21:13 -04:00
|
|
|
// #include <SITL/SIM_Frsky_SPort.h>
|
|
|
|
// #include <SITL/SIM_Frsky_SPortPassthrough.h>
|
2019-11-20 22:11:42 -04:00
|
|
|
#include <SITL/SIM_PS_RPLidarA2.h>
|
2020-12-07 07:07:21 -04:00
|
|
|
#include <SITL/SIM_PS_TeraRangerTower.h>
|
2020-12-08 06:13:41 -04:00
|
|
|
#include <SITL/SIM_PS_LightWare_SF45B.h>
|
2019-12-16 22:21:13 -04:00
|
|
|
|
2019-10-28 23:53:01 -03:00
|
|
|
#include <SITL/SIM_RichenPower.h>
|
2021-06-28 19:24:15 -03:00
|
|
|
#include <SITL/SIM_FETtecOneWireESC.h>
|
2016-01-01 02:09:07 -04:00
|
|
|
#include <AP_HAL/utility/Socket.h>
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
class HAL_SITL;
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
class HALSITL::SITL_State {
|
2016-01-10 02:23:32 -04:00
|
|
|
friend class HALSITL::Scheduler;
|
|
|
|
friend class HALSITL::Util;
|
2016-07-21 21:58:02 -03:00
|
|
|
friend class HALSITL::GPIO;
|
2012-12-14 21:54:26 -04:00
|
|
|
public:
|
|
|
|
void init(int argc, char * const argv[]);
|
|
|
|
|
|
|
|
enum vehicle_type {
|
2015-05-04 21:59:07 -03:00
|
|
|
ArduCopter,
|
2020-03-26 21:51:15 -03:00
|
|
|
Rover,
|
2017-10-27 14:24:53 -03:00
|
|
|
ArduPlane,
|
2021-03-18 00:12:54 -03:00
|
|
|
ArduSub,
|
|
|
|
Blimp
|
2012-12-14 21:54:26 -04:00
|
|
|
};
|
|
|
|
|
2015-06-29 19:55:02 -03:00
|
|
|
uint16_t pwm_output[SITL_NUM_CHANNELS];
|
2016-01-03 17:22:02 -04:00
|
|
|
uint16_t pwm_input[SITL_RC_INPUT_CHANNELS];
|
2017-08-07 09:05:52 -03:00
|
|
|
bool output_ready = false;
|
2015-03-21 11:27:25 -03:00
|
|
|
bool new_rc_input;
|
|
|
|
void loop_hook(void);
|
2015-05-04 21:59:07 -03:00
|
|
|
uint16_t base_port(void) const {
|
|
|
|
return _base_port;
|
|
|
|
}
|
2012-12-17 22:34:13 -04:00
|
|
|
|
2021-10-26 09:31:22 -03:00
|
|
|
// create a simulated serial device; type of device is given by
|
|
|
|
// name parameter
|
|
|
|
SITL::SerialDevice *create_serial_sim(const char *name, const char *arg);
|
2017-08-10 07:23:11 -03:00
|
|
|
|
2016-05-16 03:51:09 -03:00
|
|
|
bool use_rtscts(void) const {
|
|
|
|
return _use_rtscts;
|
|
|
|
}
|
|
|
|
|
2013-11-28 06:43:25 -04:00
|
|
|
// simulated airspeed, sonar and battery monitor
|
2015-03-21 11:27:25 -03:00
|
|
|
uint16_t sonar_pin_value; // pin 0
|
2022-05-16 02:27:01 -03:00
|
|
|
uint16_t airspeed_pin_value[AIRSPEED_MAX_SENSORS]; // pin 1
|
2015-03-21 11:27:25 -03:00
|
|
|
uint16_t voltage_pin_value; // pin 13
|
|
|
|
uint16_t current_pin_value; // pin 12
|
2018-03-07 22:11:05 -04:00
|
|
|
uint16_t voltage2_pin_value; // pin 15
|
|
|
|
uint16_t current2_pin_value; // pin 14
|
2012-12-18 03:42:48 -04:00
|
|
|
|
2015-11-03 16:59:43 -04:00
|
|
|
// paths for UART devices
|
2021-04-26 17:47:21 -03:00
|
|
|
const char *_uart_path[9] {
|
2015-11-03 16:59:43 -04:00
|
|
|
"tcp:0:wait",
|
|
|
|
"GPS1",
|
|
|
|
"tcp:2",
|
|
|
|
"tcp:3",
|
2016-04-19 21:08:35 -03:00
|
|
|
"GPS2",
|
2017-06-23 16:45:26 -03:00
|
|
|
"tcp:5",
|
2018-06-29 04:51:14 -03:00
|
|
|
"tcp:6",
|
2021-04-26 17:47:21 -03:00
|
|
|
"tcp:7",
|
|
|
|
"tcp:8",
|
2015-11-03 16:59:43 -04:00
|
|
|
};
|
2020-08-23 03:24:22 -03:00
|
|
|
std::vector<struct AP_Param::defaults_table_struct> cmdline_param;
|
2019-08-15 03:52:50 -03:00
|
|
|
|
|
|
|
/* parse a home location string */
|
|
|
|
static bool parse_home(const char *home_str,
|
|
|
|
Location &loc,
|
|
|
|
float &yaw_degrees);
|
|
|
|
|
2020-12-30 15:56:35 -04:00
|
|
|
/* lookup a location in locations.txt */
|
|
|
|
static bool lookup_location(const char *home_str,
|
|
|
|
Location &loc,
|
|
|
|
float &yaw_degrees);
|
|
|
|
|
2020-12-28 10:33:56 -04:00
|
|
|
uint8_t get_instance() const { return _instance; }
|
|
|
|
|
2012-12-14 21:54:26 -04:00
|
|
|
private:
|
|
|
|
void _parse_command_line(int argc, char * const argv[]);
|
2015-05-04 18:08:42 -03:00
|
|
|
void _set_param_default(const char *parm);
|
2012-12-14 21:54:26 -04:00
|
|
|
void _usage(void);
|
2021-12-11 05:49:33 -04:00
|
|
|
void _sitl_setup();
|
2012-12-14 21:54:26 -04:00
|
|
|
void _setup_fdm(void);
|
|
|
|
void _setup_timer(void);
|
|
|
|
void _setup_adc(void);
|
|
|
|
|
2016-11-19 02:21:54 -04:00
|
|
|
void set_height_agl(void);
|
2021-12-07 21:49:53 -04:00
|
|
|
void _update_rangefinder();
|
2016-07-13 10:27:56 -03:00
|
|
|
void _set_signal_handlers(void) const;
|
|
|
|
|
2017-05-11 10:38:32 -03:00
|
|
|
void _update_airspeed(float airspeed);
|
2016-09-21 14:15:00 -03:00
|
|
|
void _check_rc_input(void);
|
2018-05-30 07:18:40 -03:00
|
|
|
bool _read_rc_sitl_input();
|
2015-05-02 07:27:33 -03:00
|
|
|
void _fdm_input_local(void);
|
2016-01-01 02:09:07 -04:00
|
|
|
void _output_to_flightgear(void);
|
2018-07-31 09:32:43 -03:00
|
|
|
void _simulator_servos(struct sitl_input &input);
|
2015-05-02 08:41:13 -03:00
|
|
|
void _fdm_input_step(void);
|
2015-05-04 21:59:07 -03:00
|
|
|
|
2015-05-02 08:41:13 -03:00
|
|
|
void wait_clock(uint64_t wait_time_usec);
|
2015-03-21 11:27:25 -03:00
|
|
|
|
2012-12-14 21:54:26 -04:00
|
|
|
// internal state
|
2015-03-21 11:27:25 -03:00
|
|
|
enum vehicle_type _vehicle;
|
2015-05-10 08:02:20 -03:00
|
|
|
uint8_t _instance;
|
2015-03-21 11:27:25 -03:00
|
|
|
uint16_t _base_port;
|
|
|
|
pid_t _parent_pid;
|
|
|
|
uint32_t _update_count;
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
Scheduler *_scheduler;
|
2015-03-21 11:27:25 -03:00
|
|
|
|
2016-01-03 17:22:02 -04:00
|
|
|
SocketAPM _sitl_rc_in{true};
|
2021-07-30 07:13:59 -03:00
|
|
|
SITL::SIM *_sitl;
|
2016-09-21 14:15:00 -03:00
|
|
|
uint16_t _rcin_port;
|
2016-11-15 10:44:51 -04:00
|
|
|
uint16_t _fg_view_port;
|
2016-11-17 14:05:04 -04:00
|
|
|
uint16_t _irlock_port;
|
2015-03-21 11:27:25 -03:00
|
|
|
float _current;
|
|
|
|
|
|
|
|
bool _synthetic_clock_mode;
|
2015-04-13 03:16:22 -03:00
|
|
|
|
2016-05-16 03:51:09 -03:00
|
|
|
bool _use_rtscts;
|
2016-09-21 14:02:15 -03:00
|
|
|
bool _use_fg_view;
|
2016-05-16 03:51:09 -03:00
|
|
|
|
2018-06-16 22:39:41 -03:00
|
|
|
const char *_fg_address;
|
2015-05-03 19:10:33 -03:00
|
|
|
|
2015-04-13 03:16:22 -03:00
|
|
|
// delay buffer variables
|
|
|
|
static const uint8_t wind_buffer_length = 50;
|
|
|
|
|
|
|
|
// airspeed sensor delay buffer variables
|
|
|
|
struct readings_wind {
|
|
|
|
uint32_t time;
|
|
|
|
float data;
|
|
|
|
};
|
|
|
|
uint8_t store_index_wind;
|
|
|
|
uint32_t last_store_time_wind;
|
|
|
|
VectorN<readings_wind,wind_buffer_length> buffer_wind;
|
|
|
|
uint32_t time_delta_wind;
|
|
|
|
uint32_t delayed_time_wind;
|
2018-04-30 12:26:15 -03:00
|
|
|
uint32_t wind_start_delay_micros;
|
2015-04-13 03:16:22 -03:00
|
|
|
|
2015-05-02 07:27:33 -03:00
|
|
|
// internal SITL model
|
2015-10-22 10:04:42 -03:00
|
|
|
SITL::Aircraft *sitl_model;
|
2015-05-10 02:36:18 -03:00
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_GIMBAL_ENABLED
|
2015-05-24 23:11:16 -03:00
|
|
|
// simulated gimbal
|
|
|
|
bool enable_gimbal;
|
2015-10-22 10:04:42 -03:00
|
|
|
SITL::Gimbal *gimbal;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2015-05-24 23:11:16 -03:00
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_ADSB_ENABLED
|
2016-06-15 00:48:43 -03:00
|
|
|
// simulated ADSb
|
2015-11-18 21:22:47 -04:00
|
|
|
SITL::ADSB *adsb;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2016-01-01 02:09:07 -04:00
|
|
|
|
2018-03-07 21:25:34 -04:00
|
|
|
// simulated vicon system:
|
|
|
|
SITL::Vicon *vicon;
|
|
|
|
|
2019-10-28 23:53:01 -03:00
|
|
|
// simulated Benewake tf02 rangefinder:
|
|
|
|
SITL::RF_Benewake_TF02 *benewake_tf02;
|
|
|
|
// simulated Benewake tf03 rangefinder:
|
|
|
|
SITL::RF_Benewake_TF03 *benewake_tf03;
|
|
|
|
// simulated Benewake tfmini rangefinder:
|
|
|
|
SITL::RF_Benewake_TFmini *benewake_tfmini;
|
2022-08-01 20:44:01 -03:00
|
|
|
// simulated TeraRanger Serial:
|
|
|
|
SITL::RF_TeraRanger_Serial *teraranger_serial;
|
2019-10-28 23:53:01 -03:00
|
|
|
|
2020-06-30 08:10:28 -03:00
|
|
|
// simulated LightWareSerial rangefinder - legacy protocol::
|
2019-10-28 23:53:01 -03:00
|
|
|
SITL::RF_LightWareSerial *lightwareserial;
|
2020-06-30 08:10:28 -03:00
|
|
|
// simulated LightWareSerial rangefinder - binary protocol:
|
|
|
|
SITL::RF_LightWareSerialBinary *lightwareserial_binary;
|
2019-10-28 23:53:01 -03:00
|
|
|
// simulated Lanbao rangefinder:
|
|
|
|
SITL::RF_Lanbao *lanbao;
|
|
|
|
// simulated BLping rangefinder:
|
|
|
|
SITL::RF_BLping *blping;
|
|
|
|
// simulated LeddarOne rangefinder:
|
|
|
|
SITL::RF_LeddarOne *leddarone;
|
2021-10-25 18:41:10 -03:00
|
|
|
// simulated USD1 v0 rangefinder:
|
|
|
|
SITL::RF_USD1_v0 *USD1_v0;
|
|
|
|
// simulated USD1 v1 rangefinder:
|
|
|
|
SITL::RF_USD1_v1 *USD1_v1;
|
2019-10-28 23:53:01 -03:00
|
|
|
// simulated MaxsonarSerialLV rangefinder:
|
|
|
|
SITL::RF_MaxsonarSerialLV *maxsonarseriallv;
|
|
|
|
// simulated Wasp rangefinder:
|
|
|
|
SITL::RF_Wasp *wasp;
|
|
|
|
// simulated NMEA rangefinder:
|
|
|
|
SITL::RF_NMEA *nmea;
|
2020-04-21 00:29:11 -03:00
|
|
|
// simulated MAVLink rangefinder:
|
|
|
|
SITL::RF_MAVLink *rf_mavlink;
|
2020-06-14 20:36:08 -03:00
|
|
|
// simulated GYUS42v2 rangefinder:
|
|
|
|
SITL::RF_GYUS42v2 *gyus42v2;
|
2019-10-28 23:53:01 -03:00
|
|
|
|
2019-12-16 22:21:13 -04:00
|
|
|
// simulated Frsky devices
|
|
|
|
SITL::Frsky_D *frsky_d;
|
|
|
|
// SITL::Frsky_SPort *frsky_sport;
|
|
|
|
// SITL::Frsky_SPortPassthrough *frsky_sportpassthrough;
|
2020-12-07 07:07:21 -04:00
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_PS_RPLIDARA2_ENABLED
|
2020-12-07 07:07:21 -04:00
|
|
|
// simulated RPLidarA2:
|
2019-11-20 22:11:42 -04:00
|
|
|
SITL::PS_RPLidarA2 *rplidara2;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2019-12-16 22:21:13 -04:00
|
|
|
|
2021-06-28 19:24:15 -03:00
|
|
|
// simulated FETtec OneWire ESCs:
|
|
|
|
SITL::FETtecOneWireESC *fetteconewireesc;
|
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED
|
2020-12-08 06:13:41 -04:00
|
|
|
// simulated SF45B proximity sensor:
|
|
|
|
SITL::PS_LightWare_SF45B *sf45b;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2020-12-08 06:13:41 -04:00
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_PS_TERARANGERTOWER_ENABLED
|
2020-12-07 07:07:21 -04:00
|
|
|
SITL::PS_TeraRangerTower *terarangertower;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2020-12-07 07:07:21 -04:00
|
|
|
|
2022-01-14 22:47:15 -04:00
|
|
|
#if AP_SIM_CRSF_ENABLED
|
2020-06-04 14:59:30 -03:00
|
|
|
// simulated CRSF devices
|
|
|
|
SITL::CRSF *crsf;
|
2022-01-14 22:47:15 -04:00
|
|
|
#endif
|
2020-06-04 14:59:30 -03:00
|
|
|
|
2020-12-29 06:30:34 -04:00
|
|
|
// simulated VectorNav system:
|
|
|
|
SITL::VectorNav *vectornav;
|
2021-04-24 21:31:35 -03:00
|
|
|
|
2021-09-23 19:26:03 -03:00
|
|
|
// simulated LORD Microstrain system
|
|
|
|
SITL::LORD *lord;
|
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_JSON_MASTER_ENABLED
|
2021-04-24 21:31:35 -03:00
|
|
|
// Ride along instances via JSON SITL backend
|
|
|
|
SITL::JSON_Master ride_along;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2021-04-24 21:31:35 -03:00
|
|
|
|
2021-11-01 04:03:23 -03:00
|
|
|
#if HAL_SIM_AIS_ENABLED
|
2021-04-11 11:42:17 -03:00
|
|
|
// simulated AIS stream
|
|
|
|
SITL::AIS *ais;
|
2021-11-01 04:03:23 -03:00
|
|
|
#endif
|
2021-04-11 11:42:17 -03:00
|
|
|
|
2021-10-10 22:12:20 -03:00
|
|
|
// simulated EFI MegaSquirt device:
|
|
|
|
SITL::EFI_MegaSquirt *efi_ms;
|
|
|
|
|
2016-01-01 02:09:07 -04:00
|
|
|
// output socket for flightgear viewing
|
|
|
|
SocketAPM fg_socket{true};
|
2015-11-18 21:22:47 -04:00
|
|
|
|
2016-01-06 18:09:40 -04:00
|
|
|
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
|
2016-06-20 22:00:36 -03:00
|
|
|
|
2020-12-28 10:33:56 -04:00
|
|
|
char *_gps_fifo[2];
|
2021-10-16 00:10:40 -03:00
|
|
|
|
|
|
|
// simulated GPS devices
|
|
|
|
SITL::GPS *gps[2]; // constrained by # of parameter sets
|
2021-12-07 21:49:53 -04:00
|
|
|
|
|
|
|
// returns a voltage between 0V to 5V which should appear as the
|
|
|
|
// voltage from the sensor
|
|
|
|
float _sonar_pin_voltage() const;
|
|
|
|
|
2012-12-14 21:54:26 -04:00
|
|
|
};
|
|
|
|
|
2020-09-12 16:04:38 -03:00
|
|
|
#endif // defined(HAL_BUILD_AP_PERIPH)
|
2015-05-04 03:15:12 -03:00
|
|
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
|