ardupilot/libraries/AP_HAL_SITL/CAN_SocketCAN.h
Andrew Tridgell b6e79d05fd HAL_SITL: support multicast UDP for CAN in SITL
this will work on windows and in WSL
2023-08-29 15:09:48 +10:00

24 lines
464 B
C++

/*
socketcan transport for SITL CAN
*/
#pragma once
#include "CAN_Transport.h"
#if HAL_NUM_CAN_IFACES && HAL_CAN_WITH_SOCKETCAN
class CAN_SocketCAN : public CAN_Transport {
public:
bool init(uint8_t instance) override;
bool send(const AP_HAL::CANFrame &frame) override;
bool receive(AP_HAL::CANFrame &frame) override;
int get_read_fd(void) const override {
return fd;
}
private:
int fd = -1;
};
#endif // HAL_NUM_CAN_IFACES