2023-08-25 21:52:28 -03:00
|
|
|
/*
|
|
|
|
multicast UDP transport for SITL CAN
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include "CAN_Transport.h"
|
|
|
|
|
|
|
|
#if HAL_NUM_CAN_IFACES
|
|
|
|
|
|
|
|
class CAN_Multicast : 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 {
|
2023-11-23 01:56:12 -04:00
|
|
|
return sock.get_read_fd();
|
2023-08-25 21:52:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
2023-11-23 01:56:12 -04:00
|
|
|
SocketAPM sock{true};
|
2023-08-25 21:52:28 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // HAL_NUM_CAN_IFACES
|