AP_Periph: allow SITL periph with more devices

This commit is contained in:
Andrew Tridgell 2023-08-18 06:27:55 +10:00 committed by Peter Barker
parent ce288856b5
commit 698e38e849
5 changed files with 25 additions and 1 deletions

View File

@ -383,6 +383,13 @@ public:
bool locked; bool locked;
} uart_monitor; } uart_monitor;
#endif #endif
#if AP_SIM_ENABLED
SITL::SIM sitl;
#if AP_AHRS_ENABLED
AP_AHRS ahrs;
#endif
#endif
}; };
namespace AP namespace AP

View File

@ -569,6 +569,18 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(g_rcin, "RC", Parameters_RCIN), GOBJECT(g_rcin, "RC", Parameters_RCIN),
#endif #endif
#if AP_SIM_ENABLED
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
GOBJECT(sitl, "SIM_", SITL::SIM),
#if AP_AHRS_ENABLED
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#endif
#endif // AP_SIM_ENABLED
AP_VAREND AP_VAREND
}; };

View File

@ -79,6 +79,8 @@ public:
k_param_networking, k_param_networking,
k_param_rpm_sensor, k_param_rpm_sensor,
k_param_g_rcin, k_param_g_rcin,
k_param_sitl,
k_param_ahrs,
}; };
AP_Int16 format_version; AP_Int16 format_version;

View File

@ -2456,7 +2456,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
uint32_t now = AP_HAL::millis(); uint32_t now = AP_HAL::millis();
static uint32_t last_update_ms; static uint32_t last_update_ms;
if (g.rangefinder_max_rate > 0 && if (g.rangefinder_max_rate > 0 &&
now - last_update_ms < 1000/g.rangefinder_max_rate) { now - last_update_ms < uint32_t(1000/g.rangefinder_max_rate)) {
// limit to max rate // limit to max rate
return; return;
} }

View File

@ -73,6 +73,9 @@ def build(bld):
'AP_RPM', 'AP_RPM',
'AP_Proximity', 'AP_Proximity',
'AP_RCProtocol', 'AP_RCProtocol',
'AP_AHRS',
'AP_Terrain',
'AP_Torqeedo',
] ]
bld.ap_stlib( bld.ap_stlib(
name= 'AP_Periph_libs', name= 'AP_Periph_libs',