ardupilot/libraries
Peter Barker 3716f5513d AP_HAL_SITL: process inbound data in outqueue-length delay loop
this is the loop which ensures the amount of data sent to the mavlink client (usually Python) is limited - if we don't do this then we lose vast amounts of data when running at large speedups.

By attempting to process inbound data we may realise that the TCP connection has been dropped, and in that case we will start to listen for another connection.

This allows you to terminate the sim_vehicle.py MAVProxy and have it automagically restart (when running under GDB).  This is very useful for testing MAVProxy patches with SITL; it's a different workflow to opening an output and connecting a new version of MAVProxy to that outout.
2024-11-12 13:54:08 +11:00
..
AC_AttitudeControl Copter: Heli: simplify autorotation mode change and support RSC autorotation state 2024-10-11 09:54:26 +11:00
AC_Autorotation AC_Autorotation: Add RSC_Autorotation class 2024-10-11 09:54:26 +11:00
AC_AutoTune AC_Autotune_Multi: Use rate step command 2024-09-26 19:25:33 +10:00
AC_Avoidance AC_Avoidance: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
AC_CustomControl AC_CustomControl: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
AC_Fence AC_Fence: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AC_InputManager
AC_PID AC_PID: AC_P_2D comment fix 2024-10-04 09:25:56 +09:00
AC_PrecLand AC_PrecLand: remove assumption about how precland update method is called 2024-09-24 10:56:57 +09:00
AC_Sprayer AC_Sprayer: create and use an AP_Sprayer_config.h 2024-07-05 14:27:45 +10:00
AC_WPNav AC_Loiter: updates to offset handling 2024-10-04 09:25:56 +09:00
AP_AccelCal AP_AccelCal: remove pointless assignment when counting calibrators 2024-01-21 09:53:04 +11:00
AP_ADC AP_ADC: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_ADSB AP_ADSB: Style fixes 2024-10-31 15:28:34 -07:00
AP_AdvancedFailsafe AP_AdvancedFailsafe: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_AHRS AP_AHRS: Change the order in which you make judgments 2024-10-25 18:13:57 +11:00
AP_Airspeed AP_Airspeed: Don't fail on REG_WHOAMI_RECHECK_ID 2024-09-17 10:36:29 +10:00
AP_AIS AP_AIS: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Arming ArduCopter: Update clang pragma to check for the version of clang that introduces the warning 2024-11-12 12:41:49 +11:00
AP_Avoidance AP_Avoidance: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Baro AP_Baro: fix example: fixing missing objects 2024-09-29 09:40:37 +10:00
AP_BattMonitor AP_BattMonitor : update metadata for fuellevel param ranges 2024-11-12 09:22:21 +11:00
AP_Beacon AP_Beacon: allow hwdefs to override number of beacons 2024-08-26 13:48:02 +10:00
AP_BLHeli AP_BLHeli:correct RVMASK metadata 2024-10-08 20:58:16 +11:00
AP_BoardConfig AP_BoardConfig: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_Button
AP_Camera AP_Camera: RunCam: get rpty channels directly using convenience functions 2024-11-06 18:40:38 +11:00
AP_CANManager AP_CANManager: Integrate methods for converting hexadecimal characters to numbers 2024-09-25 08:48:44 +10:00
AP_CheckFirmware AP_CheckFirmware: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Common AP_Common: Location: add set_alt_m 2024-11-06 18:12:48 +11:00
AP_Compass AP_Compass: Also mark Z axis as calibrations, just like the XY 2024-11-05 09:25:59 +09:00
AP_CSVReader
AP_CustomRotations AP_CustomRotations: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_DAL AP_DAL: document more replay messages 2024-10-15 10:46:45 +11:00
AP_DDS AP_DDS: Vehicle status interface 2024-11-12 12:01:45 +11:00
AP_Declination
AP_Devo_Telem
AP_DroneCAN AP_DroneCAN: support FlexDebug message 2024-11-05 17:03:23 +09:00
AP_EFI AP_EFI: Hirth: fix sensor health bitmask 2024-09-13 18:52:48 +10:00
AP_ESC_Telem AP_ESC_Telem: tidy old calls to _telem_data 2024-09-11 10:23:00 +10:00
AP_ExternalAHRS AP_ExternalAHRS: support backends with get_variances() 2024-10-23 06:46:59 +09:00
AP_ExternalControl
AP_FETtecOneWire AP_FETtecOneWire: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Filesystem AP_Filesystem: support port SITL to OpenBSD 2024-11-06 14:17:31 +11:00
AP_FlashIface
AP_FlashStorage
AP_Follow AP_Follow: use set_alt_m when possible 2024-11-08 10:54:39 +11:00
AP_Frsky_Telem AP_Frsky_Telem: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
AP_Generator AP_Generator: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_GPS AP_GPS: use AP_GPS_FixType for ExternalAHRS fix type 2024-10-01 10:32:11 +10:00
AP_Gripper AP_Gripper: correct emitting of grabbed/released messages 2024-06-20 10:59:14 +10:00
AP_GSOF AP_GSOF: Use sparse endian instead of custom code 2024-08-26 13:31:49 +10:00
AP_GyroFFT AP_GyroFFT: move to new constant dt low pass filter class 2024-08-20 09:09:41 +10:00
AP_HAL AP_HAL: tidy defaulting of Bebop OpticalFlow sensor type 2024-11-12 12:45:29 +11:00
AP_HAL_ChibiOS AP_HAL_ChibiOS: tidy defaulting of OpticalFlow sensor type 2024-11-12 12:45:29 +11:00
AP_HAL_Empty AP_HAL_Empty: removed run_debug_shell 2024-07-11 07:42:54 +10:00
AP_HAL_ESP32 AP_HAL_ESP32: RCOutput ported to new mcpwm driver 2024-10-27 21:19:29 +11:00
AP_HAL_Linux AP_HAL_Linux: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
AP_HAL_QURT HAL_QURT: added install script 2024-11-08 12:02:45 +11:00
AP_HAL_SITL AP_HAL_SITL: process inbound data in outqueue-length delay loop 2024-11-12 13:54:08 +11:00
AP_Hott_Telem AP_Hott_Telem: disable Hott telemetry by default 2024-08-06 09:30:49 +10:00
AP_IBus_Telem AP_IBus_Telem: Initial implementation 2024-08-07 14:01:44 +10:00
AP_ICEngine AP_ICEngine: fix send_text severities 2024-09-27 16:12:28 +10:00
AP_InertialNav AP_InertialNav: remove use of AP_AHRS from most headers 2024-09-03 10:35:54 +10:00
AP_InertialSensor AP_InertialSensor: optimize Invensense v3 FIF read 2024-11-12 11:36:59 +11:00
AP_InternalError AP_InternalError: fix signedness issue with snprintf 2024-05-22 23:22:23 +10:00
AP_IOMCU AP_IOMCU: use RC_Channel to populate IOMCU mappings 2024-11-12 13:10:14 +11:00
AP_IRLock
AP_JSButton AP_JSButton: add SURFTRAK mode 2024-02-21 18:59:20 -03:00
AP_JSON AP_JSON: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_KDECAN AP_KDECAN: standardize on 32 bit microsecond CAN timeouts 2024-10-11 09:51:43 +11:00
AP_L1_Control AP_L1_Control: make reached_loiter_target() more reliable 2024-10-01 07:15:44 +10:00
AP_Landing AP_Landing: restart_landing_sequence get current location and pass it to get_landing_sequence_start 2024-04-02 11:11:59 +11:00
AP_LandingGear AP_LandingGear: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_LeakDetector AP_LeakDetector: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Logger AP_Logger: Add enums to VER message 2024-11-12 11:11:45 +11:00
AP_LTM_Telem AP_LTM_Telem: disable LTM telemetry by default 2024-08-06 09:30:49 +10:00
AP_Math AP_Math: move zeroing to header, use memset, reuse in identity 2024-11-05 08:39:25 +09:00
AP_Menu AP_Menu: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Mission AP_Mission: do not use float functions on integers 2024-11-12 11:22:30 +11:00
AP_Module AP_Module: remove use of AP_AHRS from most headers 2024-09-03 10:35:54 +10:00
AP_Motors AP_MotorsHeli: Consolidate all autorotation state into its own class within RSC 2024-10-11 09:54:26 +11:00
AP_Mount AP_Mount: tidy header includes 2024-11-12 13:02:43 +11:00
AP_MSP AP_MSP: MSP_RAW_GPS cog should be decidegrees not centidegrees 2024-09-13 12:45:22 +10:00
AP_NavEKF AP_NavEKF: add enumeration to document EKF SolutionStatus 2024-11-05 08:59:42 +09:00
AP_NavEKF2 AP_NavEKF2: clarify wind direction descriptions 2024-10-08 20:57:36 +11:00
AP_NavEKF3 AP_NavEKF3: add an option_is_enabled method 2024-11-12 12:20:44 +11:00
AP_Navigation
AP_Networking AP_Networking: add connector loopback test for Ethernet 2024-09-19 11:44:22 +10:00
AP_NMEA_Output AP_NMEA_Output: stop passing serial manager to GPS init 2024-03-19 07:28:55 +11:00
AP_Notify AP_Notify: Add GPIO driver and buzzer 2024-10-01 21:06:39 -05:00
AP_OLC
AP_ONVIF AP_ONVIF: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_OpenDroneID Copter: Give better error in opendroneid build when DID_ENABLE=0. 2024-09-17 09:17:24 +10:00
AP_OpticalFlow AP_OpticalFlow: tidy defaulting of Bebop OpticalFlow sensor type 2024-11-12 12:45:29 +11:00
AP_OSD AP_OSD: don't go via RCMap singleton to get RPTY RC channels 2024-09-17 22:10:53 +10:00
AP_Parachute AP_Parachute: remove AUX_FUNC entries based on feature defines 2024-09-08 00:55:43 +10:00
AP_Param AP_Param: add and use global NaNf float value 2024-09-26 19:26:59 +10:00
AP_PiccoloCAN AP_PiccoloCAN: use 32 bit microsecond timeouts for write_frame 2024-10-15 10:24:25 +11:00
AP_Proximity AP_Proximity_DroneCAN: fix code stype 2024-09-10 23:36:44 +10:00
AP_Radio AP_Radio: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_Rally AP_Rally: add ASSERT_STORAGE_SIZE macro 2024-01-22 22:44:05 +11:00
AP_RAMTRON
AP_RangeFinder AP_RangeFinder: Move the flag setting location of has_data 2024-09-29 09:40:20 +10:00
AP_RCMapper AP_RCMapper: exclude body of AP_RCMapper based on AP_RCMAPPER_ENABLED 2024-04-17 18:17:56 +10:00
AP_RCProtocol AP_RCProtocol: get rid of compiler warning from clang about unknown warning group -Wswitch-unreachable 2024-10-26 21:05:33 +11:00
AP_RCTelemetry AP_RCTelemetry: Fix Baro and Vario values 2024-11-05 09:36:51 +09:00
AP_Relay AP_Relay: added relay output invert function 2024-04-06 10:58:43 +11:00
AP_RobotisServo AP_RobotisServo: Send register write values as little-endian 2024-09-27 11:53:06 +10:00
AP_ROMFS AP_ROMFS: clarify usage and null termination 2024-05-04 10:15:44 +10:00
AP_RPM AP_RPM: Allow more instances 2024-08-10 22:37:03 +10:00
AP_RSSI AP_RSSI: make metadata more consistent 2024-07-02 11:34:29 +10:00
AP_RTC AP_RTC: use gmtime_r() instead of gmtime() 2024-02-21 12:09:48 +11:00
AP_SBusOut
AP_Scheduler AP_Scheduler: Use a range of values here because it is valid to do so. 2024-11-05 09:25:59 +09:00
AP_Scripting AP_Scripting: mount-djirs2: increase bus/mount setup flexibility 2024-11-08 10:47:41 +11:00
AP_SerialLED
AP_SerialManager AP_SerialManager: RegisteredPort, add bytes_per_second/baudrate methods 2024-10-08 10:42:21 +11:00
AP_ServoRelayEvents
AP_SmartRTL AP_SmartRTL: add point made public 2024-07-24 17:22:44 +10:00
AP_Soaring AP_Soaring: remove use of AP_AHRS from most headers 2024-09-03 10:35:54 +10:00
AP_Stats AP_Stats: update flight time on disarm 2024-04-05 11:31:20 +11:00
AP_SurfaceDistance AP_SurfaceDistance: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
AP_TECS AP_TECS: Reverted pitch limitation order 2024-10-02 17:09:07 +10:00
AP_TempCalibration AP_TempCalibration: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_TemperatureSensor AP_Temperature: fix MCP9600 i2c address and TEMP9 index 2024-10-15 11:30:30 +11:00
AP_Terrain AP_Terrain: split sending terrain report from terrain request 2024-10-01 10:13:06 +10:00
AP_Torqeedo AP_Torqeedo: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
AP_Tuning AP_Tuning: allow compilation with HAL_LOGGING_ENABLED false 2024-01-17 18:25:55 +11:00
AP_Vehicle AP_Vehicle: Add @LoggerEnum tags around APM_BUILD #defines 2024-11-12 11:11:45 +11:00
AP_VideoTX AP_VideoTX:add additional freq bands(RushFPV 3.3GHz) 2024-08-13 21:32:56 +10:00
AP_VisualOdom AP_VisualOdom: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AP_Volz_Protocol AP_Volz_Protocol: update logging format with integer change 2024-11-11 23:48:43 +00:00
AP_WheelEncoder AP_WheelEncoder: correct initialisation of WheelRateController objects 2024-09-24 10:46:34 +09:00
AP_Winch AP_Winch: correct compilation when backends compiled out 2024-08-12 18:28:27 +10:00
AP_WindVane AP_WindVane: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
APM_Control APM_Control: Correct use of deceleration 2024-11-04 11:55:28 +09:00
AR_Motors AR_Motors: use GCS_SEND_TEXT rather than gcs().send_text 2024-08-07 18:33:16 +10:00
AR_WPNav AR_WPNav: re-order initialiser lines so -Werror=reorder will work 2024-09-24 22:50:28 +10:00
doc treewide: fix shebangs - /bin/bash -> /usr/bin/env bash 2024-02-13 11:36:23 +11:00
Filter Filter: only update notch on init if fixed 2024-09-09 09:29:32 +10:00
GCS_MAVLink GCS_MAVLink: use set_alt_m 2024-11-06 18:12:48 +11:00
PID
RC_Channel RC_Channel: add accessor for channel number 2024-09-25 08:46:55 +10:00
SITL SITL: correct MCP9600 simulation 2024-11-08 12:33:37 +11:00
SRV_Channel SRV_Channel: added lift_release 2024-09-10 10:15:34 +10:00
StorageManager StorageManager: use NEW_NOTHROW for new(std::nothrow) 2024-06-04 09:20:21 +10:00
COLCON_IGNORE