mirror of https://github.com/ArduPilot/ardupilot
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.
This commit is contained in:
parent
adcf5d3503
commit
c05441b959
|
@ -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());
|
||||
|
||||
|
|
Loading…
Reference in New Issue