mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: If HAL_CAN_WITH_SOCKETCAN is undefined, treat it as NONE
This commit is contained in:
parent
edaddc0431
commit
7731fc09e2
|
@ -219,11 +219,11 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
|
||||||
case SITL::SIM::CANTransport::MulticastUDP:
|
case SITL::SIM::CANTransport::MulticastUDP:
|
||||||
transport = NEW_NOTHROW CAN_Multicast();
|
transport = NEW_NOTHROW CAN_Multicast();
|
||||||
break;
|
break;
|
||||||
case SITL::SIM::CANTransport::SocketCAN:
|
|
||||||
#if HAL_CAN_WITH_SOCKETCAN
|
#if HAL_CAN_WITH_SOCKETCAN
|
||||||
|
case SITL::SIM::CANTransport::SocketCAN:
|
||||||
transport = NEW_NOTHROW CAN_SocketCAN();
|
transport = NEW_NOTHROW CAN_SocketCAN();
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
case SITL::SIM::CANTransport::None:
|
case SITL::SIM::CANTransport::None:
|
||||||
default: // if user supplies an invalid value for the parameter
|
default: // if user supplies an invalid value for the parameter
|
||||||
transport = nullptr;
|
transport = nullptr;
|
||||||
|
|
Loading…
Reference in New Issue