From d3ea7b0ca692b0311e5c662ff73dcdf7264c8a04 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 15 Jan 2023 15:55:38 +1100 Subject: [PATCH] SITL: added SIM_UART_LOSS parameter --- libraries/SITL/SITL.cpp | 7 +++++++ libraries/SITL/SITL.h | 2 ++ 2 files changed, 9 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index c5257286eb..86f5253ef5 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -325,6 +325,13 @@ const AP_Param::GroupInfo SIM::var_info3[] = { AP_GROUPINFO("ESC_ARM_RPM", 41, SIM, esc_rpm_armed, 0.0f), + // @Param: UART_LOSS + // @DisplayName: UART byte loss percentage + // @Description: Sets percentage of outgoing byte loss on UARTs + // @Units: % + // @User: Advanced + AP_GROUPINFO("UART_LOSS", 42, SIM, uart_byte_loss_pct, 0), + AP_SUBGROUPINFO(airspeed[0], "ARSPD_", 50, SIM, SIM::AirspeedParm), #if AIRSPEED_MAX_SENSORS > 1 AP_SUBGROUPINFO(airspeed[1], "ARSPD2_", 51, SIM, SIM::AirspeedParm), diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index f6c40dc810..45d8d45760 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -236,6 +236,8 @@ public: AP_Int16 loop_time_jitter_us; AP_Int32 on_hardware_output_enable_mask; // mask of output channels passed through to actual hardware + AP_Float uart_byte_loss_pct; + #ifdef SFML_JOYSTICK AP_Int8 sfml_joystick_id; AP_Int8 sfml_joystick_axis[8];