Ardupilot2/libraries/SITL
Shiv Tyagi 5167cd1e48 SITL: set z component of precland device pos separately
The position vector passed to update method is relative to home and the precland device origin height is also relative to home. Hence, we
can set the height of precland origin separately in a 3d vec containing its position relative to home
2022-08-05 10:17:19 +10:00
..
examples SITL: fix python files exec permissions 2022-06-08 08:16:42 +09:00
tests SITL: tests: only build on sitl 2022-04-26 10:26:29 +10:00
tools
picojson.h
SIM_ADSB.cpp SITL: make SITL::ADSB a SITL::SerialDevice 2021-11-23 11:09:29 +11:00
SIM_ADSB.h SITL: make SITL::ADSB a SITL::SerialDevice 2021-11-23 11:09:29 +11:00
SIM_Aircraft.cpp SITL: params always use set method 2022-08-03 13:43:48 +01:00
SIM_Aircraft.h SITL: use AP_SIM_ENABLED define more 2022-04-26 10:26:29 +10:00
SIM_AirSim.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_AirSim.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_Airspeed_DLVR.cpp SITL: make C_TO_KELVIN a function macro; create KELVIN_TO_C 2022-01-13 18:31:46 +11:00
SIM_Airspeed_DLVR.h
SIM_AIS_data.txt SITL: add SIM_AIS 2021-08-10 08:11:18 +09:00
SIM_AIS.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_AIS.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_BalanceBot.cpp SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_BalanceBot.h
SIM_Balloon.cpp
SIM_Balloon.h
SIM_Battery.cpp
SIM_Battery.h
SIM_BattMonitor_SMBus_Generic.cpp SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_BattMonitor_SMBus_Generic.h SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_BattMonitor_SMBus_Maxell.cpp SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10: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: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_BattMonitor_SMBus_Rotoye.h
SIM_BattMonitor_SMBus.cpp SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_BattMonitor_SMBus.h SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_Blimp.cpp SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_Blimp.h SITL: Blimp SITL add initial dynamics 2021-09-18 08:26:23 +10:00
SIM_Buzzer.cpp SITL: SIM_Buzzer: hide params if not WITH_SITL_TONEALARM 2022-08-02 10:49:11 +10:00
SIM_Buzzer.h SITL: Change build errors 2022-03-08 14:37:21 -08:00
SIM_Calibration.cpp
SIM_Calibration.h
SIM_CRRCSim.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_CRRCSim.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_CRSF.cpp SITL : Update Telemetry 2022-01-17 11:26:34 +09:00
SIM_CRSF.h SITL: add compilation option AP_SIM_CRSF_ENABLED 2022-01-15 21:56:33 +11:00
SIM_EFI_MegaSquirt.cpp SITL: move simulated megasquirt to SerialDevice framework 2021-10-17 10:00:08 +11:00
SIM_EFI_MegaSquirt.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_FETtecOneWireESC.cpp SITL: avoid use of stderr/::fprintf 2021-10-12 09:00:17 +11:00
SIM_FETtecOneWireESC.h SITL: Fix multi #include's 2021-12-21 10:38:46 +11:00
SIM_FlightAxis.cpp SITL: fill in wind from flightaxis 2022-08-02 07:49:34 +10:00
SIM_FlightAxis.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_Frame.cpp SITL: SIM_Frame: add number of motors to json spec 2022-05-03 10:03:07 +10:00
SIM_Frame.h SITL: SIM_Frame: add number of motors to json spec 2022-05-03 10:03:07 +10:00
SIM_Frsky_D.cpp SITL : Update Telemetry 2022-01-17 11:26:34 +09:00
SIM_Frsky_D.h
SIM_Frsky.cpp SITL : Update Telemetry 2022-01-17 11:26:34 +09:00
SIM_Frsky.h
SIM_Gazebo.cpp SITL: tidy includes 2022-05-03 09:14:58 +10:00
SIM_Gazebo.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_Gimbal.cpp SITL: Gimbal make some printfs #if GIMBAL_DEBUG 2022-01-12 18:03:27 +11:00
SIM_Gimbal.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_GPS.cpp SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_GPS.h SITL: split AP_HAL_SITL and AP_SIM_ENABLED 2022-03-17 14:39:55 +11:00
SIM_Gripper_EPM.cpp SITL: avoid use of stderr/::fprintf 2021-10-12 09:00:17 +11:00
SIM_Gripper_EPM.h
SIM_Gripper_Servo.cpp SITL: avoid use of stderr/::fprintf 2021-10-12 09:00:17 +11:00
SIM_Gripper_Servo.h
SIM_Helicopter.cpp SITL: helicopter add update_external_payload() for sensors 2022-01-19 18:21:32 +11:00
SIM_Helicopter.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_I2C.cpp SITL: SIM_BattMonitor_SMBus add registers to smartbatts 2022-05-02 10:56:39 +10:00
SIM_I2C.h
SIM_I2CDevice.cpp SITL: add simulated MCP9600 2021-10-19 08:15:00 +11:00
SIM_I2CDevice.h SITL: add simulated MCP9600 2021-10-19 08:15:00 +11:00
SIM_ICEngine.cpp SITL: add tests for ICE Planes 2022-07-01 19:33:51 +10:00
SIM_ICEngine.h SITL: add tests for ICE Planes 2022-07-01 19:33:51 +10:00
SIM_ICM40609.h
SIM_IntelligentEnergy24.cpp SITL: correct format string in SIM_IntelligentEnergy24 2021-10-21 13:01:49 +11:00
SIM_IntelligentEnergy24.h
SIM_IntelligentEnergy.cpp
SIM_IntelligentEnergy.h
SIM_Invensense_v3.cpp SITL: use enumeration in place of O_RDWR for I2C register defs 2021-10-12 14:44:31 +11:00
SIM_Invensense_v3.h SITL: use enumeration in place of O_RDWR for I2C register defs 2021-10-12 14:44:31 +11:00
SIM_JEDEC_MX25L3206E.cpp SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_JEDEC_MX25L3206E.h SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_JEDEC.cpp SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_JEDEC.h SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_JSBSim.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_JSBSim.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_JSON_Master.cpp SITL : correct comment spelling 2022-05-24 20:27:45 +09:00
SIM_JSON_Master.h SITL : correct comment spelling 2022-05-24 20:27:45 +09:00
SIM_JSON.cpp SITL : correct comment spelling 2022-05-24 20:27:45 +09:00
SIM_JSON.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_last_letter.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_last_letter.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_LORD.cpp Tools: autotest: add test for LORD EAHRS 2021-10-17 08:55:03 +11:00
SIM_LORD.h Tools: autotest: add test for LORD EAHRS 2021-10-17 08:55:03 +11:00
SIM_MaxSonarI2CXL.h
SIM_Morse.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_Morse.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_Motor.cpp SITL: Make Yaw control scale with aircraft size 2022-07-19 09:24:45 +10:00
SIM_Motor.h SITL: Make Yaw control scale with aircraft size 2022-07-19 09:24:45 +10:00
SIM_MotorBoat.h
SIM_MS5XXX.cpp SITL: avoid use of stderr/::fprintf 2021-10-12 09:00:17 +11:00
SIM_MS5XXX.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_MS5525.cpp SITL: fixed up airspeed parameters 2022-05-17 19:34:32 +10:00
SIM_MS5525.h SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_MS5611.cpp SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_MS5611.h SITL: MS5XXX drivers use check_conversion_accuracy 2021-09-21 09:30:58 +10:00
SIM_Multicopter.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_Multicopter.h
SIM_Parachute.cpp
SIM_Parachute.h
SIM_Plane.cpp SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_Plane.h SITL: add tests for ICE Planes 2022-07-01 19:33:51 +10:00
SIM_Precland.cpp SITL: set z component of precland device pos separately 2022-08-05 10:17:19 +10:00
SIM_Precland.h SIM_Precland: add option to set orientation of precland device in sitl 2022-06-16 12:43:55 +10:00
SIM_PS_LightWare_SF45B.cpp SITL: correct PS_LightWare_SF45B simulator 2022-02-17 09:23:29 +11:00
SIM_PS_LightWare_SF45B.h SITL: correct altitude of suggested test location 2022-02-17 09:23:29 +11:00
SIM_PS_LightWare.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_PS_RPLidarA2.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_PS_RPLidarA2.h SITL: correct altitude of suggested test location 2022-02-17 09:23:29 +11:00
SIM_PS_TeraRangerTower.cpp SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_PS_TeraRangerTower.h SITL: correct altitude of suggested test location 2022-02-17 09:23:29 +11:00
SIM_QuadPlane.cpp SITL: add copter tailsitter 2021-10-26 10:03:00 +11:00
SIM_QuadPlane.h
SIM_RAMTRON_FM25V02.cpp SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_RAMTRON_FM25V02.h SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_RAMTRON.cpp SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_RAMTRON.h SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_RF_Benewake_TF02.h
SIM_RF_Benewake_TF03.h
SIM_RF_Benewake_TFmini.h
SIM_RF_Benewake.cpp
SIM_RF_Benewake.h
SIM_RF_BLping.cpp
SIM_RF_BLping.h
SIM_RF_GYUS42v2.cpp
SIM_RF_GYUS42v2.h
SIM_RF_Lanbao.cpp
SIM_RF_Lanbao.h
SIM_RF_LeddarOne.cpp
SIM_RF_LeddarOne.h
SIM_RF_LightWareSerial.cpp SITL: LightwareSerial: return 130m when out-of-range-high 2021-11-23 18:20:58 +11:00
SIM_RF_LightWareSerial.h
SIM_RF_LightWareSerialBinary.cpp
SIM_RF_LightWareSerialBinary.h
SIM_RF_MAVLink.cpp SITL/SIM_RF_MAVLink: fix incomplete initializer clauses 2022-07-01 18:24:43 +09:00
SIM_RF_MAVLink.h
SIM_RF_MaxsonarSerialLV.cpp
SIM_RF_MaxsonarSerialLV.h
SIM_RF_NMEA.cpp SITL: NMEA Depthfinder add temperature simulation 2021-10-15 13:08:17 +11:00
SIM_RF_NMEA.h SITL: NMEA Depthfinder add temperature simulation 2021-10-15 13:08:17 +11:00
SIM_RF_USD1_v0.cpp SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_USD1_v0.h SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_USD1_v1.cpp SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_USD1_v1.h SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_USD1.cpp SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_USD1.h SITL: rename uLanding files to USD1 2021-10-26 15:31:12 +11:00
SIM_RF_Wasp.cpp
SIM_RF_Wasp.h
SIM_RichenPower.cpp SITL: SIM_RichenPower sets MaintenanceRequired error flag 2022-05-25 18:17:05 +10:00
SIM_RichenPower.h SITL: SIM_RichenPower sets MaintenanceRequired error flag 2022-05-25 18:17:05 +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_Sailboat.cpp SITL: SIM_Sailboat: remove use of AHRS 2021-08-30 13:40:37 +10:00
SIM_Sailboat.h
SIM_Scrimmage.cpp SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_Scrimmage.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_SerialDevice.cpp SITL: use SITL::SerialDevice in place of pipe for communication 2021-11-06 16:54:07 +11:00
SIM_SerialDevice.h SITL: use SITL::SerialDevice in place of pipe for communication 2021-11-06 16:54:07 +11:00
SIM_SerialProximitySensor.cpp SITL: add SIM_SONAR_ROT, use it for measuring horizontal distances 2022-04-19 10:26:10 +10:00
SIM_SerialProximitySensor.h SITL: add SIM_SONAR_ROT, use it for measuring horizontal distances 2022-04-19 10:26:10 +10:00
SIM_SerialRangeFinder.cpp SITL: make C_TO_KELVIN a function macro; create KELVIN_TO_C 2022-01-13 18:31:46 +11:00
SIM_SerialRangeFinder.h SITL: NMEA Depthfinder add temperature simulation 2021-10-15 13:08:17 +11:00
SIM_Ship.cpp SITL: don't use adjusted terrain in SITL 2022-03-28 16:01:21 +11:00
SIM_Ship.h SITL: added ship offset and ATTITUDE 2022-03-10 07:34:20 +11:00
SIM_SilentWings.cpp SITL: fix executable permission and trailing whitespace 2022-06-08 08:16:42 +09:00
SIM_SilentWings.h SITL: fix executable permission and trailing whitespace 2022-06-08 08:16:42 +09:00
SIM_SingleCopter.cpp SITL: added is_lock_step_scheduled() API 2021-05-24 20:13:37 +10:00
SIM_SingleCopter.h
SIM_SMBusDevice.cpp SITL: use enumeration in place of O_RDWR for I2C register defs 2021-10-12 14:44:31 +11:00
SIM_SMBusDevice.h SITL: use enumeration in place of O_RDWR for I2C register defs 2021-10-12 14:44:31 +11:00
SIM_SPI.cpp SITL: allow JEDEC/RAMTRON to be compiled out 2022-01-15 13:50:21 +11:00
SIM_SPI.h SITL: add simulated SPI devices 2021-10-12 20:01:49 +11:00
SIM_SPIDevice.h SITL: add simulated SPI devices 2021-10-12 20:01:49 +11:00
SIM_Sprayer.cpp
SIM_Sprayer.h
SIM_Submarine.cpp SITL: correct submarine rangefinding 2021-12-11 20:10:10 +11:00
SIM_Submarine.h SITL: permit double-precision maths in SITL even on embedded hardware 2022-03-17 14:39:55 +11:00
SIM_Temperature_MCP9600.cpp SITL: add simulated MCP9600 2021-10-19 08:15:00 +11:00
SIM_Temperature_MCP9600.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_Temperature_TSYS01.cpp SITL: fix labs on unsigned value subtraction 2021-05-26 17:40:19 +10:00
SIM_Temperature_TSYS01.h
SIM_ToneAlarm.cpp
SIM_ToneAlarm.h
SIM_ToshibaLED.cpp SITL: make ToshibaLED simulator optional 2021-11-02 09:40:09 +11:00
SIM_ToshibaLED.h SITL: make ToshibaLED simulator optional 2021-11-02 09:40:09 +11:00
SIM_Tracker.cpp
SIM_Tracker.h
SIM_VectorNav.cpp
SIM_VectorNav.h SITL: nuke clang warnings 2022-03-03 16:34:14 +11:00
SIM_Vicon.cpp SITL: support simulation of ODOMETRY message 2021-12-27 12:32:41 +11:00
SIM_Vicon.h SITL: support simulation of ODOMETRY message 2021-12-27 12:32:41 +11:00
SIM_Webots.cpp WEBOTS_SITL: adjust_params model 2021-11-16 13:30:12 +11:00
SIM_Webots.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SIM_XPlane.cpp SITL: remove transitive include dependencies 2022-07-20 17:32:24 +10:00
SIM_XPlane.h SITL: provide HAL_x_ENABLED for many SITL features 2021-10-12 09:04:55 +11:00
SITL_Input.h SITL: move to 32 servo outs 2022-05-22 12:07:37 +10:00
SITL.cpp SITL: added SIM_VIB_MOT_HMNC parameter 2022-07-03 18:47:33 +10:00
SITL.h SITL: params always use set method 2022-08-03 13:43:48 +01:00