From 0a77f877159bd82d0cf2d093e22df50462e66419 Mon Sep 17 00:00:00 2001 From: JacobCrabill Date: Tue, 15 Mar 2022 17:22:27 -0700 Subject: [PATCH] mavlink: Replace CONFIG_NET with CONFIG_NET_UDP Allows use of SocketCAN w/o also enabling UDP support in NuttX --- src/modules/mavlink/mavlink_main.cpp | 12 ++++++------ src/modules/mavlink/mavlink_main.h | 4 ++-- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index b72e566fed..7086586fc9 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -765,12 +765,12 @@ void Mavlink::send_finish() else if (get_protocol() == Protocol::UDP) { -# if defined(CONFIG_NET) +# if defined(CONFIG_NET_UDP) if (_src_addr_initialized) { # endif // CONFIG_NET ret = sendto(_socket_fd, _buf, _buf_fill, 0, (struct sockaddr *)&_src_addr, sizeof(_src_addr)); -# if defined(CONFIG_NET) +# if defined(CONFIG_NET_UDP) } # endif // CONFIG_NET @@ -1849,7 +1849,7 @@ Mavlink::task_main(int argc, char *argv[]) bool err_flag = false; int myoptind = 1; const char *myoptarg = nullptr; -#if defined(CONFIG_NET) || defined(__PX4_POSIX) +#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX) int temp_int_arg; #endif @@ -3270,7 +3270,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50 PRINT_MODULE_USAGE_PARAM_STRING('d', "/dev/ttyS1", "", "Select Serial Device", true); PRINT_MODULE_USAGE_PARAM_INT('b', 57600, 9600, 3000000, "Baudrate (can also be p:)", true); PRINT_MODULE_USAGE_PARAM_INT('r', 0, 10, 10000000, "Maximum sending data rate in B/s (if 0, use baudrate / 20)", true); -#if defined(CONFIG_NET) || defined(__PX4_POSIX) +#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX) PRINT_MODULE_USAGE_PARAM_FLAG('p', "Enable Broadcast", true); PRINT_MODULE_USAGE_PARAM_INT('u', 14556, 0, 65536, "Select UDP Network Port (local)", true); PRINT_MODULE_USAGE_PARAM_INT('o', 14550, 0, 65536, "Select UDP Network Port (remote)", true); @@ -3291,7 +3291,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50 PRINT_MODULE_USAGE_COMMAND_DESCR("stop-all", "Stop all instances"); PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop a running instance"); -#if defined(CONFIG_NET) || defined(__PX4_POSIX) +#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX) PRINT_MODULE_USAGE_PARAM_INT('u', -1, 0, 65536, "Select Mavlink instance via local Network Port", true); #endif PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Select Mavlink instance via Serial Device", true); @@ -3301,7 +3301,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50 PRINT_MODULE_USAGE_ARG("streams", "Print all enabled streams", true); PRINT_MODULE_USAGE_COMMAND_DESCR("stream", "Configure the sending rate of a stream for a running instance"); -#if defined(CONFIG_NET) || defined(__PX4_POSIX) +#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX) PRINT_MODULE_USAGE_PARAM_INT('u', -1, 0, 65536, "Select Mavlink instance via local Network Port", true); #endif PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, "", "Select Mavlink instance via Serial Device", true); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 536928d9f0..d2265068e5 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -53,7 +53,7 @@ #include #endif -#if defined(CONFIG_NET) || !defined(__PX4_NUTTX) +#if defined(CONFIG_NET_UDP) || !defined(__PX4_NUTTX) #include #include #endif @@ -90,7 +90,7 @@ #define HASH_PARAM "_HASH_CHECK" -#if defined(CONFIG_NET) || defined(__PX4_POSIX) +#if defined(CONFIG_NET_UDP) || defined(__PX4_POSIX) # define MAVLINK_UDP # define DEFAULT_REMOTE_PORT_UDP 14550 ///< GCS port per MAVLink spec #endif // CONFIG_NET || __PX4_POSIX diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c66300c057..bcbeeec50d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3091,7 +3091,7 @@ MavlinkReceiver::run() #if defined(__PX4_POSIX) /* 1500 is the Wifi MTU, so we make sure to fit a full packet */ uint8_t buf[1600 * 5]; -#elif defined(CONFIG_NET) +#elif defined(CONFIG_NET_UDP) /* 1500 is the Wifi MTU, so we make sure to fit a full packet */ uint8_t buf[1000]; #else