From c1595c6cf1f9bef6e41bc976b2c8a4bd590d0937 Mon Sep 17 00:00:00 2001 From: Jeevan K Date: Tue, 21 Jan 2025 20:11:42 +0530 Subject: [PATCH] SITL : Add ACC_TRIM, ARSPD documentation --- libraries/SITL/SITL.cpp | 5 +++++ libraries/SITL/SITL_Airspeed.cpp | 11 ++++++++++- 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index f97f7a2116..cfa334fe56 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -1119,6 +1119,11 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Vector3Parameter: 1 AP_GROUPINFO("ACC3_SCAL", 24, SIM, accel_scale[2], 0), #endif + // @Param: ACC_TRIM + // @DisplayName: Accelerometer trim + // @Description: Trim applied to simulated accelerometer + // @User: Advanced + // @Vector3Parameter: 1 AP_GROUPINFO("ACC_TRIM", 25, SIM, accel_trim, 0), #if APM_BUILD_TYPE(APM_BUILD_Rover) diff --git a/libraries/SITL/SITL_Airspeed.cpp b/libraries/SITL/SITL_Airspeed.cpp index ea1289386b..f06a244287 100644 --- a/libraries/SITL/SITL_Airspeed.cpp +++ b/libraries/SITL/SITL_Airspeed.cpp @@ -5,8 +5,17 @@ namespace SITL { // user settable parameters for airspeed sensors const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = { - // user settable parameters for the 1st airspeed sensor + // @Param: RND + // @DisplayName: Airspeed sensor noise + // @Description: Simulated Airspeed sensor noise + // @Units: Pa + // @User: Advanced AP_GROUPINFO("RND", 1, AirspeedParm, noise, 2.0), + // @Param: OFS + // @DisplayName: Airspeed sensor offset + // @Description: Simulated Airspeed sensor offset + // @Units: m/s + // @User: Advanced AP_GROUPINFO("OFS", 2, AirspeedParm, offset, 2013), // @Param: FAIL // @DisplayName: Airspeed sensor failure