Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Create separate option for bridging mcast and hw can #28913

Open
wants to merge 4 commits into
base: master
Choose a base branch
from

Conversation

bugobliterator
Copy link
Member

@bugobliterator bugobliterator commented Dec 20, 2024

  • Bridging between mcast CAN and HW CAN needs to be turned off by default. The reason is if there are more than 2 devices on the same HW CAN and Ethernet network that will cause network loops and potentially choke the CAN bus.
  • Bridging needs to be always turned off for Bootloaders, and in the case of AP_Periph and ardupilot, it should be enabled by the user.

Changes done:

  • Change option name from CAN1_MCAST_GATEWAY to CAN1_MCAST_ENDPOINT in NET_OPTIONS.
  • Adds another option CAN1_MCAST_BRIDGED to enable bridging between MCAST and Hw CAN.
  • Bridging option can be changed and will take effect on the same run, reboot is not required.

struct {
#ifndef HAL_BOOTLOADER_BUILD
HAL_Semaphore sem;
#endif
// allow up to 3 callbacks per interface
FrameCb cb[3];
bool rx_cb_disable[3];
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why do we need these disable flags? if we want to disable, why don't we just call unregister_frame_callback()?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@tridge the disable is only to remove calling on rx, but we still call the callback on tx from CANIface. Basically we don't forward what we receive from CAN Bus, but we still transmit frames that are to be sent out. That's how we leave the interaction with the device itself functional. Unregistering will remove the call from both tx and rx.

@bugobliterator bugobliterator requested a review from tridge January 14, 2025 00:18
@tridge
Copy link
Contributor

tridge commented Jan 22, 2025

@bugobliterator could this be handled in the callback in the AP_Networking layer?

@tridge tridge removed the DevCallEU label Jan 22, 2025
@bugobliterator
Copy link
Member Author

@bugobliterator could this be handled in the callback in the AP_Networking layer?

I don't think there's a way to do this without changes to CANIface, there's a common callback for both RX and TX. We have to either pass the direction as callback parameter, make it part of each frame or the way I have done which is to have the direction selection per callback. First method will require wider changes, second one costs more memory and third one I think is a happy middle.

@@ -64,9 +64,9 @@ int16_t AP_HAL::CANIface::receive(CANFrame& out_frame, uint64_t& out_ts_monotoni
#ifndef HAL_BOOTLOADER_BUILD
WITH_SEMAPHORE(callbacks.sem);
#endif
for (auto &cb : callbacks.cb) {
if (cb != nullptr) {
cb(get_iface_num(), out_frame);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

adding an bool is_send as an additional field in the callback
maybe change

    FUNCTOR_TYPEDEF(FrameCb, void, uint8_t, const AP_HAL::CANFrame &);

to this:

    FUNCTOR_TYPEDEF(FrameCb, void, uint8_t, const AP_HAL::CANFrame &, uint8_t flags);

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

or could be a bool

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Moved to using CANIOFlags actually to keep things consistent.

Also changed IsMAVCAN flag to IsForwardedFrame. This flag is then used to check if the frame was forwarded from different physical iface.

libraries/AP_Networking/AP_Networking.cpp Outdated Show resolved Hide resolved
libraries/AP_Networking/AP_Networking.h Outdated Show resolved Hide resolved
libraries/AP_Networking/AP_Networking_CAN.cpp Outdated Show resolved Hide resolved
libraries/AP_Networking/AP_Networking_CAN.cpp Outdated Show resolved Hide resolved
also add option to enable multicast with bridging to CAN bus in application
and disabled in bootloader
Copy link
Member Author

@bugobliterator bugobliterator left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

requested changes made

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this looks much better, thank you!
just the one trivial fix needed then should be merged

const bool bridged = false;
#endif

if (flags & AP_HAL::CANIface::IsForwardedFrame && !bridged) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we need parentheses around the bitmask test, or some compilers will complain

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Status: No status
Development

Successfully merging this pull request may close these issues.

4 participants