From 46cf0fccb69a61a6e3940663375f3207a60c043b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 27 Aug 2024 13:12:15 +1000 Subject: [PATCH] AP_DDS: remove instance check for DDS Client this is probably a flow of control problem. But the code block below this resets some state variables before returning, and will also return false in the same case this removed block does. Resetting that state might be very important to the caller. --- libraries/AP_DDS/AP_DDS_Client.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index eb54a54eff09f..41d71b35a2c56 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -123,11 +123,6 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i // https://www.fluentcpp.com/2021/12/13/the-evolutions-of-lambdas-in-c14-c17-and-c20/ // constexpr auto times2 = [] (sensor_msgs_msg_NavSatFix* msg) { return n * 2; }; - // assert(instance >= GPS_MAX_RECEIVERS); - if (instance >= GPS_MAX_RECEIVERS) { - return false; - } - auto &gps = AP::gps(); WITH_SEMAPHORE(gps.get_semaphore());