Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_DDS: Publish all available GPS instances #29419

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 6 additions & 7 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,7 +209,6 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i

auto &gps = AP::gps();
WITH_SEMAPHORE(gps.get_semaphore());

if (!gps.is_healthy(instance)) {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If the GPS goes unhealthy, we still need to publish it. Existing problem.

msg.status.status = -1; // STATUS_NO_FIX
msg.status.service = 0; // No services supported
Expand All @@ -219,13 +218,12 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i

// No update is needed
const auto last_fix_time_ms = gps.last_fix_time_ms(instance);
if (last_nav_sat_fix_time_ms == last_fix_time_ms) {
if (last_nav_sat_fix_time_ms[instance] == last_fix_time_ms) {
return false;
} else {
last_nav_sat_fix_time_ms = last_fix_time_ms;
last_nav_sat_fix_time_ms[instance] = last_fix_time_ms;
}


update_topic(msg.header.stamp);
static_assert(GPS_MAX_RECEIVERS <= 9, "GPS_MAX_RECEIVERS is greater than 9");
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
Expand Down Expand Up @@ -1682,9 +1680,10 @@ void AP_DDS_Client::update()
}
#endif // AP_DDS_TIME_PUB_ENABLED
#if AP_DDS_NAVSATFIX_PUB_ENABLED
constexpr uint8_t gps_instance = 0;
if (update_topic(nav_sat_fix_topic, gps_instance)) {
write_nav_sat_fix_topic();
for (uint8_t gps_instance = 0; gps_instance < GPS_MAX_INSTANCES; gps_instance++) {
if (update_topic(nav_sat_fix_topic, gps_instance)) {
write_nav_sat_fix_topic();
}
}
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
#if AP_DDS_BATTERY_STATE_PUB_ENABLED
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_DDS/AP_DDS_Client.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#endif // AP_DDS_TIME_PUB_ENABLED
#if AP_DDS_NAVSATFIX_PUB_ENABLED
#include "sensor_msgs/msg/NavSatFix.h"
#include <AP_GPS/AP_GPS_config.h>
#endif // AP_DDS_NAVSATFIX_PUB_ENABLED
#if AP_DDS_NEEDS_TRANSFORMS
#include "tf2_msgs/msg/TFMessage.h"
Expand Down Expand Up @@ -172,7 +173,7 @@ class AP_DDS_Client
#if AP_DDS_NAVSATFIX_PUB_ENABLED
sensor_msgs_msg_NavSatFix nav_sat_fix_topic;
// The last ms timestamp AP_DDS wrote a NavSatFix message
uint64_t last_nav_sat_fix_time_ms;
uint64_t last_nav_sat_fix_time_ms[GPS_MAX_INSTANCES];
//! @brief Serialize the current nav_sat_fix state and publish to the IO stream(s)
void write_nav_sat_fix_topic();
bool update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) WARN_IF_UNUSED;
Expand Down
Loading