ardupilot/libraries/SITL
Peter Barker 94ad32b91c SITL: remove HIL_MODE vestiges 2021-10-12 08:57:05 +11:00
..
examples SITL: remove HIL_MODE vestiges 2021-10-12 08:57:05 +11:00
tests SITL: sim_MS5611 fix simulated driver for 32bit usage 2021-09-28 09:15:11 +10:00
tools SITL: sailboat add matlab VPP tool 2018-10-09 16:27:10 +09:00
SIM_ADSB.cpp SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_ADSB.h SITL: ADSB: Don't hard code the emitter type 2019-11-26 11:57:29 +11:00
SIM_AIS.cpp SITL: add SIM_AIS 2021-08-10 08:11:18 +09:00
SIM_AIS.h SITL: add SIM_AIS 2021-08-10 08:11:18 +09:00
SIM_AIS_data.txt SITL: add SIM_AIS 2021-08-10 08:11:18 +09:00
SIM_AirSim.cpp SITL: mark logger Write() calls as streaming where appropriate 2021-08-18 10:20:03 +10:00
SIM_AirSim.h SITL: Airsim: Add support for rangefinder sensor data 2020-09-02 17:25:43 +10:00
SIM_Aircraft.cpp SITL: fixed plane-tailsitter model 2021-08-19 12:08:54 +10:00
SIM_Aircraft.h SITL: add simulated FETtec ESC 2021-08-13 16:22:37 +10:00
SIM_Airspeed_DLVR.cpp SITL: airspeed DLVR add atmosphere temperature model 2021-09-21 09:30:58 +10:00
SIM_Airspeed_DLVR.h SITL: add simulated DLVR airspeed sensor 2020-12-22 23:07:24 +11:00
SIM_BalanceBot.cpp SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_BalanceBot.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Balloon.cpp SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_Balloon.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_BattMonitor_SMBus.cpp SITL: Change the Kelvin value to a defined name 2021-01-20 20:27:19 +11:00
SIM_BattMonitor_SMBus.h SITL: correct SMBus block reads 2021-01-05 14:45:20 +11:00
SIM_BattMonitor_SMBus_Generic.cpp SITL: add maxell to i2c bus and make it 14-cells 2021-06-15 09:46:26 +10:00
SIM_BattMonitor_SMBus_Generic.h SITL: add maxell to i2c bus and make it 14-cells 2021-06-15 09:46:26 +10:00
SIM_BattMonitor_SMBus_Maxell.cpp SITL: add Maxell SMBus battery support 2020-10-26 20:34:05 +11:00
SIM_BattMonitor_SMBus_Maxell.h SITL: add maxell to i2c bus and make it 14-cells 2021-06-15 09:46:26 +10:00
SIM_BattMonitor_SMBus_Rotoye.cpp SITL: correct SMBus block reads 2021-01-05 14:45:20 +11:00
SIM_BattMonitor_SMBus_Rotoye.h SITL: add simulator for Rotoye battery monitor 2020-11-11 19:27:21 +11:00
SIM_Battery.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Battery.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Blimp.cpp SITL: Blimp SITL add initial dynamics 2021-09-18 08:26:23 +10:00
SIM_Blimp.h SITL: Blimp SITL add initial dynamics 2021-09-18 08:26:23 +10:00
SIM_Buzzer.cpp SITL: add a simulated buzzer 2019-10-16 16:00:35 +11:00
SIM_Buzzer.h SITL: add a simulated buzzer 2019-10-16 16:00:35 +11:00
SIM_CRRCSim.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_CRRCSim.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_CRSF.cpp SITL: add CRSF simulation driver 2020-07-07 18:48:06 +10:00
SIM_CRSF.h SITL: add CRSF simulation driver 2020-07-07 18:48:06 +10:00
SIM_Calibration.cpp SITL: remove use of Vector3 as function 2020-06-16 11:06:47 +10:00
SIM_Calibration.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_EFI_MegaSquirt.cpp SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_EFI_MegaSquirt.h SITL: added MegaSquirt EFI simulation 2019-11-17 20:10:54 +11:00
SIM_FETtecOneWireESC.cpp SITL: correct SIM_FETtecOneWire consume function 2021-08-23 13:47:35 +10:00
SIM_FETtecOneWireESC.h SITL: add simulated FETtec ESC 2021-08-13 16:22:37 +10:00
SIM_FlightAxis.cpp SITL: cope with a socket error in FlightAxis 2021-09-16 14:31:10 +10:00
SIM_FlightAxis.h SITL: cope with a socket error in FlightAxis 2021-09-16 14:31:10 +10:00
SIM_Frame.cpp SITL: swap rotation direciton of motor 2 for lower yaw offset 2021-08-28 10:32:59 +09:00
SIM_Frame.h SITL: Add momentum drag to multicopter model 2020-12-11 15:21:41 +11:00
SIM_Frsky.cpp SITL: add simulated Frsky devices 2020-01-08 23:53:48 +11:00
SIM_Frsky.h SITL: add simulated Frsky devices 2020-01-08 23:53:48 +11:00
SIM_Frsky_D.cpp SITL: adjust for START_STOP_D now not polluting global namespace 2020-09-30 23:14:40 +10:00
SIM_Frsky_D.h SITL: add simulated Frsky devices 2020-01-08 23:53:48 +11:00
SIM_Gazebo.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_Gazebo.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_Gimbal.cpp SITL: fixed string warnings 2020-09-15 09:40:03 +10:00
SIM_Gimbal.h SITL: simulate Solo gimbal parameter handling 2018-11-24 11:00:37 +11:00
SIM_Gripper_EPM.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Gripper_EPM.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Gripper_Servo.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Gripper_Servo.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Helicopter.cpp SITL: make heli-blade simulation work 2021-09-08 14:33:19 +10:00
SIM_Helicopter.h SITL: make heli-blade simulation work 2021-09-08 14:33:19 +10:00
SIM_I2C.cpp SITL: add simulated ms5611 baro 2021-07-14 17:46:15 +10:00
SIM_I2C.h SITL: add support for multiple i2c buses 2020-12-24 16:05:49 +11:00
SIM_I2CDevice.cpp SITL: add simulator for ICM40609 2021-01-12 17:43:36 +11:00
SIM_I2CDevice.h SITL: move from HAL_NO_GCS to HAL_GCS_ENABLED 2021-09-22 21:37:00 +10:00
SIM_ICEngine.cpp SITL: rearrange Grippers and Sprayers in SITL 2018-07-31 23:34:43 +10:00
SIM_ICEngine.h SITL: rearrange Grippers and Sprayers in SITL 2018-07-31 23:34:43 +10:00
SIM_ICM40609.h SITL: add simulator for ICM40609 2021-01-12 17:43:36 +11:00
SIM_IntelligentEnergy.cpp SITL: add simulator for IntelligentEnergy 2.4kWh 2020-11-24 12:54:52 +11:00
SIM_IntelligentEnergy.h SITL: add simulator for IntelligentEnergy 2.4kWh 2020-11-24 12:54:52 +11:00
SIM_IntelligentEnergy24.cpp SITL: add simulator for IntelligentEnergy 2.4kWh 2020-11-24 12:54:52 +11:00
SIM_IntelligentEnergy24.h SITL: add simulator for IntelligentEnergy 2.4kWh 2020-11-24 12:54:52 +11:00
SIM_Invensense_v3.cpp SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_Invensense_v3.h SITL: add simulator for ICM40609 2021-01-12 17:43:36 +11:00
SIM_JSBSim.cpp SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_JSBSim.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_JSON.cpp SITL: mark logger Write() calls as streaming where appropriate 2021-08-18 10:20:03 +10:00
SIM_JSON.h SITL: SIM_JSON: add no time sync to JSON format 2021-08-03 09:22:19 +10:00
SIM_JSON_Master.cpp SITL: mark logger Write() calls as streaming where appropriate 2021-08-18 10:20:03 +10:00
SIM_JSON_Master.h SITL: add JSON Master 2021-08-03 09:22:19 +10:00
SIM_MS5XXX.cpp SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MS5XXX.h SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MS5525.cpp SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MS5525.h SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MS5611.cpp SITL: sim_MS5611 fix simulated driver for 32bit usage 2021-09-28 09:15:11 +10:00
SIM_MS5611.h SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MaxSonarI2CXL.h SITL: factor out an I2C command/response class from simulated MaxSonar sensor 2020-12-05 09:35:53 +11:00
SIM_Morse.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_Morse.h SITL: support for steering/throttle rover 2020-02-13 09:04:32 +11:00
SIM_Motor.cpp SITL: fixed order of rotations in tilt vehicles 2021-06-08 19:11:32 +10:00
SIM_Motor.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_MotorBoat.h SITL: added a MotorBoat class 2019-09-23 17:22:01 +10:00
SIM_Multicopter.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_Multicopter.h SITL: quadplane updates 2020-02-22 11:15:37 +11:00
SIM_PS_LightWare.h SITL: add simulated SF45B 2020-12-09 21:32:36 +11:00
SIM_PS_LightWare_SF45B.cpp SITL: SF45B: increase resolution to 1 degree 2021-02-04 20:50:21 +11:00
SIM_PS_LightWare_SF45B.h SITL: move from HAL_NO_GCS to HAL_GCS_ENABLED 2021-09-22 21:37:00 +10:00
SIM_PS_RPLidarA2.cpp SITL: improve simulated serial proximity sensor 2020-12-08 09:21:06 +11:00
SIM_PS_RPLidarA2.h SITL: improve instructions for using simulated RPLidarA2 sensor 2020-12-08 09:21:06 +11:00
SIM_PS_TeraRangerTower.cpp SITL: fix build for macos systems 2021-01-21 13:09:21 +11:00
SIM_PS_TeraRangerTower.h SITL: add terarangertower simulator 2020-12-08 09:21:06 +11:00
SIM_Parachute.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Parachute.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Plane.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_Plane.h SITL: delete unused parameter 'Vector3f &body_accel' in Plane::calculate_forces() 2020-12-30 18:59:12 +11:00
SIM_Precland.cpp SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Precland.h SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_QuadPlane.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_QuadPlane.h SITL: quadplane updates 2020-02-22 11:15:37 +11:00
SIM_RF_BLping.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_BLping.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_Benewake.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_Benewake.h SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_Benewake_TF02.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_Benewake_TF03.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_Benewake_TFmini.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_GYUS42v2.cpp SITL: add simulated GY-US42-v2 rangefinder 2020-07-04 13:40:10 +10:00
SIM_RF_GYUS42v2.h SITL: add simulated GY-US42-v2 rangefinder 2020-07-04 13:40:10 +10:00
SIM_RF_Lanbao.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_Lanbao.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_LeddarOne.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_LeddarOne.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_LightWareSerial.cpp SITL: fixed build with no GCS 2020-11-10 16:15:45 +11:00
SIM_RF_LightWareSerial.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_LightWareSerialBinary.cpp SITL: add simulated LightWare serial lidar talking new binary protocol 2020-07-02 10:50:59 +10:00
SIM_RF_LightWareSerialBinary.h SITL: add simulated LightWare serial lidar talking new binary protocol 2020-07-02 10:50:59 +10:00
SIM_RF_MAVLink.cpp SITL: correct max_distance in simulated mavlink rangefinder 2021-01-06 15:33:41 +11:00
SIM_RF_MAVLink.h SITL: add simulated mavlink-attached rangefinder 2020-04-21 20:44:59 +10:00
SIM_RF_MaxsonarSerialLV.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_MaxsonarSerialLV.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_NMEA.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_NMEA.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_Wasp.cpp SITL: fixed build with no GCS 2020-11-10 16:15:45 +11:00
SIM_RF_Wasp.h SITL: increase Wasp reading frequency 2019-12-02 19:07:03 +11:00
SIM_RF_uLanding.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_uLanding.h SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_uLanding_v0.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_uLanding_v0.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RF_uLanding_v1.cpp SITL: add support for simulated serial rangefinders 2019-11-08 20:12:28 +11:00
SIM_RF_uLanding_v1.h SITL: improve testing instructions for simulated rangefinders 2019-11-09 08:01:53 +11:00
SIM_RichenPower.cpp SITL: correct simulation of RichenPower generator 2020-08-05 16:26:19 +09:00
SIM_RichenPower.h SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_Rover.cpp SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Rover.h SITL: add rover with vectored thrust support 2021-04-08 08:47:07 +09:00
SIM_SMBusDevice.cpp SITL: correct SMBus block reads 2021-01-05 14:45:20 +11:00
SIM_SMBusDevice.h SITL: correct SMBus block reads 2021-01-05 14:45:20 +11:00
SIM_Sailboat.cpp SITL: SIM_Sailboat: remove use of AHRS 2021-08-30 13:40:37 +10:00
SIM_Sailboat.h SITL: added a MotorBoat class 2019-09-23 17:22:01 +10:00
SIM_Scrimmage.cpp SITL: simulations optimisations 2020-06-06 08:17:25 +10:00
SIM_Scrimmage.h SITL: Don't start scrimmage from ArduPilot 2020-04-28 11:09:51 +10:00
SIM_SerialDevice.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_SerialDevice.h SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_SerialProximitySensor.cpp SITL: change class name from SITL::SITL to SITL::SIM 2021-08-05 07:25:31 +10:00
SIM_SerialProximitySensor.h SITL: improve simulated serial proximity sensor 2020-12-08 09:21:06 +11:00
SIM_SerialRangeFinder.cpp SITL: move calculation of simulated rangefinder range to inside SIM_Aircraft 2020-08-04 21:40:21 +10:00
SIM_SerialRangeFinder.h SITL: move calculation of simulated rangefinder range to inside SIM_Aircraft 2020-08-04 21:40:21 +10:00
SIM_Ship.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_Ship.h SITL: added ship takeoff/landing simulation 2020-07-10 13:28:38 +10:00
SIM_SilentWings.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_SilentWings.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_SingleCopter.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_SingleCopter.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_Sprayer.cpp SITL: fix DisplayName and description of parameter 2020-02-18 09:29:15 +11:00
SIM_Sprayer.h SITL: rearrange Grippers and Sprayers in SITL 2018-07-31 23:34:43 +10:00
SIM_Submarine.cpp SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Submarine.h SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Temperature_TSYS01.cpp SITL: fix labs on unsigned value subtraction 2021-05-26 17:40:19 +10:00
SIM_Temperature_TSYS01.h SITL: add support for simulated TSYS01 temperature sensor 2021-01-05 12:01:51 +11:00
SIM_ToneAlarm.cpp SITL: create SITL tonealarm files to hold enable parameter 2019-10-16 16:00:35 +11:00
SIM_ToneAlarm.h SITL: create SITL tonealarm files to hold enable parameter 2019-10-16 16:00:35 +11:00
SIM_ToshibaLED.cpp SITL: make ToshibaLED an 8-bit register device 2020-11-12 21:19:55 +11:00
SIM_ToshibaLED.h SITL: make ToshibaLED an 8-bit register device 2020-11-12 21:19:55 +11:00
SIM_Tracker.cpp SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_Tracker.h SITL: Add missing const in member functions 2021-02-03 18:45:14 +11:00
SIM_VectorNav.cpp SITL: added VectorNav simulator 2021-01-05 21:13:12 +11:00
SIM_VectorNav.h SITL: added VectorNav simulator 2021-01-05 21:13:12 +11:00
SIM_Vicon.cpp SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Vicon.h SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_Webots.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_Webots.h SITL: SITL-Webots timing is received from Webots only 2020-05-14 18:05:16 +10:00
SIM_XPlane.cpp SITL: separate origin and home in SITL 2021-07-14 17:34:40 +10:00
SIM_XPlane.h SITL: convert to double precision for positions 2021-06-24 21:34:30 +10:00
SIM_last_letter.cpp SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SIM_last_letter.h SITL: remove home_str from constructor 2019-08-15 15:16:11 +10:00
SITL.cpp SITL: cope with BARO_MAX_INSTANCES < 3 2021-09-29 10:51:14 +10:00
SITL.h SITL: remove mtk GPSs 2021-09-29 17:28:59 +10:00
SITL_Input.h SITL: rearrange Grippers and Sprayers in SITL 2018-07-31 23:34:43 +10:00
picojson.h SITL: allow loading of model from ROMFS 2020-10-28 14:20:44 +11:00