SITL: added SIM_CAN_TYPE0 and SIM_CAN_TYPE1
this selects the transport to use for CAN
This commit is contained in:
parent
b6e79d05fd
commit
3508d7eaa9
@ -105,6 +105,24 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CAN_SRV_MSK", 29, SIM, can_servo_mask, 0),
|
||||
|
||||
#if HAL_NUM_CAN_IFACES > 0
|
||||
// @Param: CAN_TYPE1
|
||||
// @DisplayName: transport type for first CAN interface
|
||||
// @Description: transport type for first CAN interface
|
||||
// @Values: 0:MulticastUDP,1:SocketCAN
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CAN_TYPE1", 30, SIM, can_transport[0], uint8_t(CANTransport::MulticastUDP)),
|
||||
#endif
|
||||
|
||||
#if HAL_NUM_CAN_IFACES > 1
|
||||
// @Param: CAN_TYPE2
|
||||
// @DisplayName: transport type for second CAN interface
|
||||
// @Description: transport type for second CAN interface
|
||||
// @Values: 0:MulticastUDP,1:SocketCAN
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CAN_TYPE2", 31, SIM, can_transport[1], uint8_t(CANTransport::MulticastUDP)),
|
||||
#endif
|
||||
|
||||
AP_GROUPINFO("SONAR_SCALE", 32, SIM, sonar_scale, 12.1212f),
|
||||
AP_GROUPINFO("FLOW_ENABLE", 33, SIM, flow_enable, 0),
|
||||
AP_GROUPINFO("TERRAIN", 34, SIM, terrain_enable, 1),
|
||||
|
@ -219,6 +219,15 @@ public:
|
||||
AP_Int8 rc_chancount; // channel count
|
||||
AP_Int8 float_exception; // enable floating point exception checks
|
||||
AP_Int32 can_servo_mask; // mask of servos/escs coming from CAN
|
||||
|
||||
#if HAL_NUM_CAN_IFACES
|
||||
enum class CANTransport : uint8_t {
|
||||
MulticastUDP = 0,
|
||||
SocketCAN = 1
|
||||
};
|
||||
AP_Enum<CANTransport> can_transport[HAL_NUM_CAN_IFACES];
|
||||
#endif
|
||||
|
||||
AP_Int8 flow_enable; // enable simulated optflow
|
||||
AP_Int16 flow_rate; // optflow data rate (Hz)
|
||||
AP_Int8 flow_delay; // optflow data delay
|
||||
|
Loading…
Reference in New Issue
Block a user