diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index e64253b79b..7011c2206b 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -219,11 +219,11 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) case SITL::SIM::CANTransport::MulticastUDP: transport = NEW_NOTHROW CAN_Multicast(); break; - case SITL::SIM::CANTransport::SocketCAN: #if HAL_CAN_WITH_SOCKETCAN + case SITL::SIM::CANTransport::SocketCAN: transport = NEW_NOTHROW CAN_SocketCAN(); -#endif break; +#endif case SITL::SIM::CANTransport::None: default: // if user supplies an invalid value for the parameter transport = nullptr;