mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SITL: add hardware relay enable mask for passing relays through to hardware
This commit is contained in:
parent
8c2627ca40
commit
8125ba1a41
@ -47,6 +47,15 @@ extern const AP_HAL::HAL& hal;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if (CONFIG_HAL_BOARD != HAL_BOARD_SITL)
|
||||
// For on-hardware, set allowed relay channels to zero.
|
||||
// Requires user to change the param to allow hadware access.
|
||||
#define SIM_DEFAULT_ENABLED_RELAY_CHANNELS 0
|
||||
#else
|
||||
// For SITL, set allowed relay channels to the full mask.
|
||||
#define SIM_DEFAULT_ENABLED_RELAY_CHANNELS UINT16_MAX
|
||||
#endif
|
||||
|
||||
namespace SITL {
|
||||
|
||||
SIM *SIM::_singleton = nullptr;
|
||||
@ -1029,6 +1038,11 @@ const AP_Param::GroupInfo SIM::var_ins[] = {
|
||||
AP_GROUPINFO("GYR5_BIAS", 47, SIM, gyro_bias[4], 0),
|
||||
#endif
|
||||
|
||||
// @Param: OH_RELAY_MSK
|
||||
// @DisplayName: SIM-on_hardware Relay Enable Mask
|
||||
// @Description: Allow relay output operation when running SIM-on-hardware
|
||||
AP_GROUPINFO("OH_RELAY_MSK", 48, SIM, on_hardware_relay_enable_mask, SIM_DEFAULT_ENABLED_RELAY_CHANNELS),
|
||||
|
||||
// the IMUT parameters must be last due to the enable parameters
|
||||
#if HAL_INS_TEMPERATURE_CAL_ENABLE
|
||||
AP_SUBGROUPINFO(imu_tcal[0], "IMUT1_", 61, SIM, AP_InertialSensor_TCal),
|
||||
|
@ -246,6 +246,7 @@ public:
|
||||
AP_Int16 loop_rate_hz;
|
||||
AP_Int16 loop_time_jitter_us;
|
||||
AP_Int32 on_hardware_output_enable_mask; // mask of output channels passed through to actual hardware
|
||||
AP_Int16 on_hardware_relay_enable_mask; // mask of relays passed through to actual hardware
|
||||
|
||||
AP_Float uart_byte_loss_pct;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user