@@ -209,7 +209,6 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i
209209
210210 auto &gps = AP::gps ();
211211 WITH_SEMAPHORE (gps.get_semaphore ());
212-
213212 if (!gps.is_healthy (instance)) {
214213 msg.status .status = -1 ; // STATUS_NO_FIX
215214 msg.status .service = 0 ; // No services supported
@@ -219,13 +218,12 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i
219218
220219 // No update is needed
221220 const auto last_fix_time_ms = gps.last_fix_time_ms (instance);
222- if (last_nav_sat_fix_time_ms == last_fix_time_ms) {
221+ if (last_nav_sat_fix_time_ms[instance] == last_fix_time_ms) {
223222 return false ;
224223 } else {
225- last_nav_sat_fix_time_ms = last_fix_time_ms;
224+ last_nav_sat_fix_time_ms[instance] = last_fix_time_ms;
226225 }
227226
228-
229227 update_topic (msg.header .stamp );
230228 static_assert (GPS_MAX_RECEIVERS <= 9 , " GPS_MAX_RECEIVERS is greater than 9" );
231229 hal.util ->snprintf (msg.header .frame_id , 2 , " %u" , instance);
@@ -1682,9 +1680,10 @@ void AP_DDS_Client::update()
16821680 }
16831681#endif // AP_DDS_TIME_PUB_ENABLED
16841682#if AP_DDS_NAVSATFIX_PUB_ENABLED
1685- constexpr uint8_t gps_instance = 0 ;
1686- if (update_topic (nav_sat_fix_topic, gps_instance)) {
1687- write_nav_sat_fix_topic ();
1683+ for (uint8_t gps_instance = 0 ; gps_instance < GPS_MAX_INSTANCES; gps_instance++) {
1684+ if (update_topic (nav_sat_fix_topic, gps_instance)) {
1685+ write_nav_sat_fix_topic ();
1686+ }
16881687 }
16891688#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
16901689#if AP_DDS_BATTERY_STATE_PUB_ENABLED
0 commit comments