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

Add AutoIP option to network options for link local addressing #27048

Closed
wants to merge 1 commit into from

Conversation

Ryanf55
Copy link
Collaborator

@Ryanf55 Ryanf55 commented May 12, 2024

Purpose

Allow a zero-configuration of IP addressing a vehicle using IPv4 link local addressing.

This is enabled with bit 1 of the NET_OPTIONS parameter enabled to turn on AUTOIP.

Link local is great because you don't need to bother with all the fiddly NET_IPADDR params.

Sensor data (such as the Trimble PX-1) can take advantage of Multicast to send sensor data to the cube, and neither the Cube nor the PX1 need to know the other's address. This makes it easier to swap hardware with less configuration.

If a DHCP server is not available on the vehicle, because LWIP_DHCP_AUTOIP_COOP is enabled on our builds, this means that LWIP will automatically start a link local address in place of that. In theory, if a DHCP server started later (such as one running on a non-RTOS linux such as PI that takes a while to boot), LWIP will drop the link local address and switch to DHCP. I haven't tested that specific case yet.

Setting up a DHCP server or static addressing on a vehicle is not easy for everyone. Setting a single bit in ArduPilot NET options is easier than that.

How to reproduce

  1. Grab a Cube Red
  2. Flash it with this branch
  3. Set the params
NET_DHCP         1           # Enable
NET_ENABLE       1
NET_GWADDR0      192
NET_GWADDR1      168
NET_GWADDR2      13
NET_GWADDR3      1
NET_IPADDR0      192
NET_IPADDR1      168
NET_IPADDR2      13
NET_IPADDR3      14
NET_MACADDR0     168
NET_MACADDR1     176
NET_MACADDR2     40
NET_MACADDR3     98
NET_MACADDR4     199
NET_MACADDR5     62
NET_NETMASK      24
NET_OPTIONS      2.0
NET_P1_TYPE      0           # Disabled
NET_P2_TYPE      0           # Disabled
NET_P3_TYPE      0           # Disabled
NET_P4_TYPE      0           # Disabled
  1. Connect the cube to your computer over ethernet
  2. Configure your ethernet adapter to link local
    image
    Or, with netplan in /etc/netplan/01-network-manager-all.yaml :
network:
  version: 2
  renderer: NetworkManager
  ethernets:
    enx503eaaa696dd:
      link-local: [ ipv4, ipv6]
  1. Reboot the cube

  2. Open mavproxy consol

  3. Observe in the logs it gets a 169.254 address, and so does your computer
    image

  4. Ping the Cube's address

Demo

image

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label May 13, 2024
@@ -148,6 +148,11 @@ void AP_Networking_ChibiOS::link_up_cb(void *p)
if (driver->frontend.get_dhcp_enabled()) {
dhcp_start(driver->thisif);
}
# if LWIP_AUTOIP
Copy link
Contributor

Choose a reason for hiding this comment

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

in lwipthread.c the lwipDefaultLinkUpCB/DownCB() functions perform the autoip before the dhcp. I don't think it matters but it would at least be nice to use the tested method that everyone else uses

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

For sure, but I was just following the docs: https://lwip.fandom.com/wiki/AUTOIP

Copy link
Collaborator Author

@Ryanf55 Ryanf55 May 14, 2024

Choose a reason for hiding this comment

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

Looking at the source code comments, there's a different recommendation:
https://github.com/ARMmbed/lwip/blob/4059748b4789fbda5970261bb075657565a1f381/src/core/ipv4/autoip.c#L22

Seems like we need to conditionally call autoip_start depending on if DHCP is enabled or not.
That said, the implementation already handles cleanly calling it mulitple times, so I don't see why we don't call this regardless, as long as it's enabled.

Copy link
Collaborator Author

@Ryanf55 Ryanf55 May 15, 2024

Choose a reason for hiding this comment

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

If it's part of the default behavior, I would expect autoip to show up if DHCP is not available but enabled, but that's not the behavior I observe.

On master, with DHCP enabled, but no DHCP server, I observe no address reported in the console logs.
image
Because AP doesn't respond to broadcast, doesn't support MDNS, and doesn't log its current address, and the configured static address doesn't work when DHCP is enabled, I'm not quite sure what's going on.

Tools/AP_Bootloader/network.cpp Outdated Show resolved Hide resolved
Tools/AP_Bootloader/network.cpp Outdated Show resolved Hide resolved
@Ryanf55 Ryanf55 marked this pull request as draft May 14, 2024 00:12
* This allows link local addressing for zero-config setup

Signed-off-by: Ryan Friedman <[email protected]>
@Ryanf55 Ryanf55 closed this Sep 21, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants