AP_DDS: Fix incorrect port param name

* We want to support TCP and UDP in the future, so make sure we call it
  UDP here

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2024-03-20 23:50:59 -06:00 committed by Andrew Tridgell
parent d4e0375d31
commit bd518dc140
1 changed files with 1 additions and 1 deletions

View File

@ -66,7 +66,7 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] {
// @Range: 1 65535 // @Range: 1 65535
// @RebootRequired: True // @RebootRequired: True
// @User: Standard // @User: Standard
AP_GROUPINFO("_PORT", 2, AP_DDS_Client, udp.port, 2019), AP_GROUPINFO("_UDP_PORT", 2, AP_DDS_Client, udp.port, 2019),
// @Group: _IP // @Group: _IP
// @Path: ../AP_Networking/AP_Networking_address.cpp // @Path: ../AP_Networking/AP_Networking_address.cpp