SITL: added SIM_UART_LOSS parameter

This commit is contained in:
Andrew Tridgell 2023-01-15 15:55:38 +11:00 committed by Peter Barker
parent dfdecc52c4
commit d3ea7b0ca6
2 changed files with 9 additions and 0 deletions

View File

@ -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),

View File

@ -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];