SITL: cope with BARO_MAX_INSTANCES < 3

This commit is contained in:
Tatsuya Yamaguchi 2021-08-31 10:45:45 +09:00 committed by Peter Barker
parent e9115601dd
commit f3173174f3
1 changed files with 4 additions and 0 deletions

View File

@ -226,8 +226,12 @@ const AP_Param::GroupInfo SIM::var_info3[] = {
AP_GROUPINFO("BARO_COUNT", 33, SIM, baro_count, 2),
AP_SUBGROUPINFO(baro[0], "BARO_", 34, SIM, SIM::BaroParm),
#if BARO_MAX_INSTANCES > 1
AP_SUBGROUPINFO(baro[1], "BAR2_", 35, SIM, SIM::BaroParm),
#endif
#if BARO_MAX_INSTANCES > 2
AP_SUBGROUPINFO(baro[2], "BAR3_", 36, SIM, SIM::BaroParm),
#endif
// user settable parameters for the 1st barometer
// @Param: BARO_RND