mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
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
This commit is contained in:
parent
fcff2e6f57
commit
1e067622d2
@ -90,7 +90,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = {
|
|||||||
// @Param: OPTIONS
|
// @Param: OPTIONS
|
||||||
// @DisplayName: Networking options
|
// @DisplayName: Networking options
|
||||||
// @Description: Networking options
|
// @Description: Networking options
|
||||||
// @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast gateway, 2:Enable CAN2 multicast gateway
|
// @Bitmask: 0:EnablePPP Ethernet gateway, 1:Enable CAN1 multicast endpoint, 2:Enable CAN2 multicast endpoint, 3:Enable CAN1 multicast bridged, 4:Enable CAN2 multicast bridged
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0),
|
AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0),
|
||||||
@ -199,14 +199,14 @@ void AP_Networking::init()
|
|||||||
start_tests();
|
start_tests();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_NETWORKING_CAN_MCAST_ENABLED && !defined(HAL_BOOTLOADER_BUILD)
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
if (option_is_set(OPTION::CAN1_MCAST_GATEWAY) || option_is_set(OPTION::CAN2_MCAST_GATEWAY)) {
|
if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT) || option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
|
||||||
// get mask of enabled buses
|
// get mask of enabled buses
|
||||||
uint8_t bus_mask = 0;
|
uint8_t bus_mask = 0;
|
||||||
if (option_is_set(OPTION::CAN1_MCAST_GATEWAY)) {
|
if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
|
||||||
bus_mask |= (1U<<0);
|
bus_mask |= (1U<<0);
|
||||||
}
|
}
|
||||||
if (option_is_set(OPTION::CAN2_MCAST_GATEWAY)) {
|
if (option_is_set(OPTION::CAN1_MCAST_ENDPOINT)) {
|
||||||
bus_mask |= (1U<<1);
|
bus_mask |= (1U<<1);
|
||||||
}
|
}
|
||||||
mcast_server.start(bus_mask);
|
mcast_server.start(bus_mask);
|
||||||
|
@ -157,14 +157,25 @@ public:
|
|||||||
enum class OPTION {
|
enum class OPTION {
|
||||||
PPP_ETHERNET_GATEWAY=(1U<<0),
|
PPP_ETHERNET_GATEWAY=(1U<<0),
|
||||||
#if AP_NETWORKING_CAN_MCAST_ENABLED
|
#if AP_NETWORKING_CAN_MCAST_ENABLED
|
||||||
CAN1_MCAST_GATEWAY=(1U<<1),
|
CAN1_MCAST_ENDPOINT=(1U<<1),
|
||||||
CAN2_MCAST_GATEWAY=(1U<<2),
|
CAN2_MCAST_ENDPOINT=(1U<<2),
|
||||||
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
CAN1_MCAST_BRIDGED=(1U<<3),
|
||||||
|
CAN2_MCAST_BRIDGED=(1U<<4),
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
bool option_is_set(OPTION option) const {
|
bool option_is_set(OPTION option) const {
|
||||||
return (param.options.get() & int32_t(option)) != 0;
|
return (param.options.get() & int32_t(option)) != 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
bool is_can_mcast_ep_bridged(uint8_t bus) const {
|
||||||
|
return (option_is_set(OPTION::CAN1_MCAST_BRIDGED) && bus == 0) ||
|
||||||
|
(option_is_set(OPTION::CAN2_MCAST_BRIDGED) && bus == 1);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static AP_Networking *singleton;
|
static AP_Networking *singleton;
|
||||||
|
|
||||||
|
@ -117,7 +117,7 @@ void AP_Networking_CAN::mcast_server(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (!cbus->register_frame_callback(
|
if (!cbus->register_frame_callback(
|
||||||
FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &),
|
FUNCTOR_BIND_MEMBER(&AP_Networking_CAN::can_frame_callback, void, uint8_t, const AP_HAL::CANFrame &, AP_HAL::CANIface::CanIOFlags),
|
||||||
callback_id)) {
|
callback_id)) {
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to register", unsigned(bus));
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "CAN_MCAST[%u]: failed to register", unsigned(bus));
|
||||||
goto de_allocate;
|
goto de_allocate;
|
||||||
@ -180,14 +180,30 @@ void AP_Networking_CAN::mcast_server(void)
|
|||||||
*/
|
*/
|
||||||
AP_HAL::CANFrame frame;
|
AP_HAL::CANFrame frame;
|
||||||
const uint16_t timeout_us = 2000;
|
const uint16_t timeout_us = 2000;
|
||||||
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
const bool bridged = AP::network().is_can_mcast_ep_bridged(bus);
|
||||||
|
#endif
|
||||||
|
|
||||||
while (frame_buffers[bus]->peek(frame)) {
|
while (frame_buffers[bus]->peek(frame)) {
|
||||||
auto retcode = get_caniface(bus)->send(frame,
|
auto *cbus = get_caniface(bus);
|
||||||
AP_HAL::micros64() + timeout_us,
|
if (cbus == nullptr) {
|
||||||
AP_HAL::CANIface::IsMAVCAN);
|
|
||||||
if (retcode == 0) {
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
if (bridged) {
|
||||||
|
auto retcode = cbus->send(frame, AP_HAL::micros64() + timeout_us,
|
||||||
|
AP_HAL::CANIface::IsForwardedFrame);
|
||||||
|
if (retcode == 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
// only call the AP_HAL::CANIface send if we are not in bridged mode
|
||||||
|
cbus->AP_HAL::CANIface::send(frame, AP_HAL::micros64() + timeout_us,
|
||||||
|
AP_HAL::CANIface::IsForwardedFrame);
|
||||||
|
}
|
||||||
|
|
||||||
// we either sent it or there was an error, either way we discard the frame
|
// we either sent it or there was an error, either way we discard the frame
|
||||||
frame_buffers[bus]->pop();
|
frame_buffers[bus]->pop();
|
||||||
}
|
}
|
||||||
@ -199,12 +215,27 @@ void AP_Networking_CAN::mcast_server(void)
|
|||||||
handler for CAN frames from the registered callback, sending frames
|
handler for CAN frames from the registered callback, sending frames
|
||||||
out as multicast UDP
|
out as multicast UDP
|
||||||
*/
|
*/
|
||||||
void AP_Networking_CAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame)
|
void AP_Networking_CAN::can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags)
|
||||||
{
|
{
|
||||||
if (bus >= HAL_NUM_CAN_IFACES || mcast_sockets[bus] == nullptr) {
|
if (bus >= HAL_NUM_CAN_IFACES || mcast_sockets[bus] == nullptr) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
// check if bridged mode is enabled
|
||||||
|
const bool bridged = AP::network().is_can_mcast_ep_bridged(bus);
|
||||||
|
#else
|
||||||
|
// never bridge in bootloader, as we can cause loops if multiple
|
||||||
|
// bootloaders with mcast are running on the same network and CAN Bus
|
||||||
|
const bool bridged = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if ((flags & AP_HAL::CANIface::IsForwardedFrame) && !bridged) {
|
||||||
|
// we don't forward frames that we received from the multicast
|
||||||
|
// server if not in bridged mode
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
struct mcast_pkt pkt {};
|
struct mcast_pkt pkt {};
|
||||||
pkt.magic = MCAST_MAGIC;
|
pkt.magic = MCAST_MAGIC;
|
||||||
pkt.flags = 0;
|
pkt.flags = 0;
|
||||||
|
@ -9,7 +9,7 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
void mcast_server(void);
|
void mcast_server(void);
|
||||||
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame);
|
void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &frame, AP_HAL::CANIface::CanIOFlags flags);
|
||||||
SocketAPM *mcast_sockets[HAL_NUM_CAN_IFACES];
|
SocketAPM *mcast_sockets[HAL_NUM_CAN_IFACES];
|
||||||
|
|
||||||
uint8_t bus_mask;
|
uint8_t bus_mask;
|
||||||
|
@ -107,6 +107,10 @@
|
|||||||
#define AP_NETWORKING_CAN_MCAST_ENABLED 0
|
#define AP_NETWORKING_CAN_MCAST_ENABLED 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED
|
||||||
|
#define AP_NETWORKING_CAN_MCAST_BRIDGING_ENABLED AP_NETWORKING_CAN_MCAST_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_NETWORKING_TESTS_ENABLED
|
#if AP_NETWORKING_TESTS_ENABLED
|
||||||
#ifndef AP_NETWORKING_TEST_IP
|
#ifndef AP_NETWORKING_TEST_IP
|
||||||
#define AP_NETWORKING_TEST_IP "192.168.144.2"
|
#define AP_NETWORKING_TEST_IP "192.168.144.2"
|
||||||
|
Loading…
Reference in New Issue
Block a user