From 72f0ecc18f2daec9bb60f6925c44a97a7bcdcca9 Mon Sep 17 00:00:00 2001 From: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> Date: Sat, 19 Oct 2024 10:52:16 -0600 Subject: [PATCH] AP_DDS: Support compile-time configurable rates for each publisher Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> --- libraries/AP_DDS/AP_DDS_Client.cpp | 18 +++++++-------- libraries/AP_DDS/AP_DDS_config.h | 36 ++++++++++++++++++++++++++++++ 2 files changed, 45 insertions(+), 9 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 9ba608c20290d..a3ae6506f0f3a 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -32,31 +32,31 @@ // Enable DDS at runtime by default static constexpr uint8_t ENABLED_BY_DEFAULT = 1; #if AP_DDS_TIME_PUB_ENABLED -static constexpr uint16_t DELAY_TIME_TOPIC_MS = 10; +static constexpr uint16_t DELAY_TIME_TOPIC_MS = AP_DDS_DELAY_TIME_TOPIC_MS; #endif // AP_DDS_TIME_PUB_ENABLED #if AP_DDS_BATTERY_STATE_PUB_ENABLED -static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = 1000; +static constexpr uint16_t DELAY_BATTERY_STATE_TOPIC_MS = AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS; #endif // AP_DDS_BATTERY_STATE_PUB_ENABLED #if AP_DDS_IMU_PUB_ENABLED -static constexpr uint16_t DELAY_IMU_TOPIC_MS = 5; +static constexpr uint16_t DELAY_IMU_TOPIC_MS = AP_DDS_DELAY_IMU_TOPIC_MS; #endif // AP_DDS_IMU_PUB_ENABLED #if AP_DDS_LOCAL_POSE_PUB_ENABLED -static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33; +static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS; #endif // AP_DDS_LOCAL_POSE_PUB_ENABLED #if AP_DDS_LOCAL_VEL_PUB_ENABLED -static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = 33; +static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS; #endif // AP_DDS_LOCAL_VEL_PUB_ENABLED #if AP_DDS_AIRSPEED_PUB_ENABLED -static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = 33; +static constexpr uint16_t DELAY_AIRSPEED_TOPIC_MS = AP_DDS_DELAY_AIRSPEED_TOPIC_MS; #endif // AP_DDS_AIRSPEED_PUB_ENABLED #if AP_DDS_GEOPOSE_PUB_ENABLED -static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = 33; +static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = AP_DDS_DELAY_GEO_POSE_TOPIC_MS; #endif // AP_DDS_GEOPOSE_PUB_ENABLED #if AP_DDS_CLOCK_PUB_ENABLED -static constexpr uint16_t DELAY_CLOCK_TOPIC_MS = 10; +static constexpr uint16_t DELAY_CLOCK_TOPIC_MS =AP_DDS_DELAY_CLOCK_TOPIC_MS; #endif // AP_DDS_CLOCK_PUB_ENABLED #if AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED -static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = 1000; +static constexpr uint16_t DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS = AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS; #endif // AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED static constexpr uint16_t DELAY_PING_MS = 500; diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index 2e0d3d6264f8c..4b82ed7465d3c 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -26,10 +26,18 @@ #define AP_DDS_IMU_PUB_ENABLED AP_DDS_EXPERIMENTAL_ENABLED #endif +#ifndef AP_DDS_DELAY_IMU_TOPIC_MS +#define AP_DDS_DELAY_IMU_TOPIC_MS 5 +#endif + #ifndef AP_DDS_TIME_PUB_ENABLED #define AP_DDS_TIME_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_TIME_TOPIC_MS +#define AP_DDS_DELAY_TIME_TOPIC_MS 10 +#endif + #ifndef AP_DDS_NAVSATFIX_PUB_ENABLED #define AP_DDS_NAVSATFIX_PUB_ENABLED 1 #endif @@ -42,30 +50,58 @@ #define AP_DDS_GPS_GLOBAL_ORIGIN_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS +#define AP_DDS_DELAY_GPS_GLOBAL_ORIGIN_TOPIC_MS 1000 +#endif + #ifndef AP_DDS_GEOPOSE_PUB_ENABLED #define AP_DDS_GEOPOSE_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_GEO_POSE_TOPIC_MS +#define AP_DDS_DELAY_GEO_POSE_TOPIC_MS 33 +#endif + #ifndef AP_DDS_LOCAL_POSE_PUB_ENABLED #define AP_DDS_LOCAL_POSE_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS +#define AP_DDS_DELAY_LOCAL_POSE_TOPIC_MS 33 +#endif + #ifndef AP_DDS_LOCAL_VEL_PUB_ENABLED #define AP_DDS_LOCAL_VEL_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS +#define AP_DDS_DELAY_LOCAL_VELOCITY_TOPIC_MS 33 +#endif + #ifndef AP_DDS_AIRSPEED_PUB_ENABLED #define AP_DDS_AIRSPEED_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_AIRSPEED_TOPIC_MS +#define AP_DDS_DELAY_AIRSPEED_TOPIC_MS 33 +#endif + #ifndef AP_DDS_BATTERY_STATE_PUB_ENABLED #define AP_DDS_BATTERY_STATE_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS +#define AP_DDS_DELAY_BATTERY_STATE_TOPIC_MS 1000 +#endif + #ifndef AP_DDS_CLOCK_PUB_ENABLED #define AP_DDS_CLOCK_PUB_ENABLED 1 #endif +#ifndef AP_DDS_DELAY_CLOCK_TOPIC_MS +#define AP_DDS_DELAY_CLOCK_TOPIC_MS 10 +#endif + #ifndef AP_DDS_JOY_SUB_ENABLED #define AP_DDS_JOY_SUB_ENABLED 1 #endif