SITL : Add ACC_TRIM, ARSPD documentation

This commit is contained in:
Jeevan K 2025-01-21 20:11:42 +05:30 committed by Peter Barker
parent 24a764c502
commit c1595c6cf1
2 changed files with 15 additions and 1 deletions

View File

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

View File

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