SITL: fixed SIM_IMU_COUNT conflict

this came from merging two PRs which both changed SITL params
This commit is contained in:
Andrew Tridgell 2020-08-28 11:31:20 +10:00
parent afa810041b
commit b18928e28e

View File

@ -211,6 +211,9 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
AP_GROUPINFO("RATE_HZ", 22, SITL, loop_rate_hz, 1200),
// count of simulated IMUs
AP_GROUPINFO("IMU_COUNT", 23, SITL, imu_count, 2),
// @Path: ./SIM_RichenPower.cpp
AP_SUBGROUPINFO(richenpower_sim, "RICH_", 31, SITL, RichenPower),
@ -249,9 +252,6 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
// user settable common airspeed parameters
AP_GROUPINFO("ARSPD_SIGN", 62, SITL, arspd_signflip, 0),
// count of simulated IMUs
AP_GROUPINFO("IMU_COUNT", 36, SITL, imu_count, 2),
AP_GROUPEND
};