ardupilot/libraries/AP_Networking/AP_Networking_CAN.h
bugobliterator 51471a0a7e AP_Networking: make can multicast an endpoint by default
also add option to enable multicast with bridging to CAN bus in application
and disabled in bootloader
2025-02-05 10:23:46 +11:00

24 lines
509 B
C++

#pragma once
#include "AP_Networking.h"
#include <AP_HAL/utility/Socket.h>
class AP_Networking_CAN {
public:
void start(const uint8_t bus_mask);
private:
void mcast_server(void);
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags);
SocketAPM *mcast_sockets[HAL_NUM_CAN_IFACES];
uint8_t bus_mask;
AP_HAL::CANIface *get_caniface(uint8_t) const;
#ifdef HAL_BOOTLOADER_BUILD
static void mcast_trampoline(void *ctx);
#endif
};