Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add documentation for SIM_ACC?_RND parameters #27592

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 0 additions & 5 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -2384,11 +2384,6 @@ def test_adsb_send_threatening_adsb_message(self, here, offset_ne=None):
def get_sim_parameter_documentation_get_whitelist(self):
# common parameters
ret = set([
"SIM_ACC1_RND",
"SIM_ACC2_RND",
"SIM_ACC3_RND",
"SIM_ACC4_RND",
"SIM_ACC5_RND",
"SIM_ACC_FILE_RW",
"SIM_ACC_TRIM_X",
"SIM_ACC_TRIM_Y",
Expand Down
16 changes: 16 additions & 0 deletions libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -924,11 +924,21 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("GYR3_RND", 10, SIM, gyro_noise[2], 0),
#endif
// @Param: ACC1_RND
// @DisplayName: Accel 1 motor noise factor
// @Description: scaling factor for simulated vibration from motors
// @User: Advanced
AP_GROUPINFO("ACC1_RND", 11, SIM, accel_noise[0], 0),
#if INS_MAX_INSTANCES > 1
// @Param: ACC2_RND
// @DisplayName: Accel 2 motor noise factor
// @CopyFieldsFrom: SIM_ACC1_RND
AP_GROUPINFO("ACC2_RND", 12, SIM, accel_noise[1], 0),
#endif
#if INS_MAX_INSTANCES > 2
// @Param: ACC3_RND
// @DisplayName: Accel 3 motor noise factor
// @CopyFieldsFrom: SIM_ACC1_RND
AP_GROUPINFO("ACC3_RND", 13, SIM, accel_noise[2], 0),
#endif
// @Param: GYR1_SCALE
Expand Down Expand Up @@ -1106,6 +1116,9 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @Vector3Parameter: 1
AP_GROUPINFO("GYR4_SCALE", 36, SIM, gyro_scale[3], 0),

// @Param: ACC4_RND
// @DisplayName: Accel 4 motor noise factor
// @CopyFieldsFrom: SIM_ACC1_RND
AP_GROUPINFO("ACC4_RND", 37, SIM, accel_noise[3], 0),

AP_GROUPINFO("GYR4_RND", 38, SIM, gyro_noise[3], 0),
Expand Down Expand Up @@ -1156,6 +1169,9 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
// @Vector3Parameter: 1
AP_GROUPINFO("GYR5_SCALE", 43, SIM, gyro_scale[4], 0),

// @Param: ACC5_RND
// @DisplayName: Accel 5 motor noise factor
// @CopyFieldsFrom: SIM_ACC1_RND
AP_GROUPINFO("ACC5_RND", 44, SIM, accel_noise[4], 0),

AP_GROUPINFO("GYR5_RND", 45, SIM, gyro_noise[4], 0),
Expand Down
Loading