Skip to content
New issue

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

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

Already on GitHub? # to your account

1.14 Release RTCM Fixes #21666

Merged
merged 3 commits into from
Jun 20, 2023
Merged
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
18 changes: 9 additions & 9 deletions src/drivers/gps/gps.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/gps_dump.h>
#include <uORB/topics/gps_inject_data.h>
#include <uORB/topics/sensor_gps.h>
Expand Down Expand Up @@ -203,7 +204,7 @@ class GPS : public ModuleBase<GPS>, public device::Device

const Instance _instance;

uORB::Subscription _orb_inject_data_sub{ORB_ID(gps_inject_data)};
uORB::SubscriptionMultiArray<gps_inject_data_s, gps_inject_data_s::MAX_INSTANCES> _orb_inject_data_sub{ORB_ID::gps_inject_data};
uORB::Publication<gps_inject_data_s> _gps_inject_data_pub{ORB_ID(gps_inject_data)};
uORB::Publication<gps_dump_s> _dump_communication_pub{ORB_ID(gps_dump)};
gps_dump_s *_dump_to_device{nullptr};
Expand Down Expand Up @@ -530,23 +531,22 @@ void GPS::handleInjectDataTopic()
// If there has not been a valid RTCM message for a while, try to switch to a different RTCM link
if ((hrt_absolute_time() - _last_rtcm_injection_time) > 5_s) {

for (uint8_t i = 0; i < gps_inject_data_s::MAX_INSTANCES; i++) {
if (_orb_inject_data_sub.ChangeInstance(i)) {
if (_orb_inject_data_sub.copy(&msg)) {
for (int instance = 0; instance < _orb_inject_data_sub.size(); instance++) {
const bool exists = _orb_inject_data_sub[instance].advertised();

if (exists) {
if (_orb_inject_data_sub[instance].copy(&msg)) {
if ((hrt_absolute_time() - msg.timestamp) < 5_s) {
// Remember that we already did a copy on this instance.
already_copied = true;
_selected_rtcm_instance = i;
_selected_rtcm_instance = instance;
break;
}
}
}
}
}

// Reset instance in case we didn't actually want to switch
_orb_inject_data_sub.ChangeInstance(_selected_rtcm_instance);

bool updated = already_copied;

// Limit maximum number of GPS injections to 8 since usually
Expand Down Expand Up @@ -574,7 +574,7 @@ void GPS::handleInjectDataTopic()
}
}

updated = _orb_inject_data_sub.update(&msg);
updated = _orb_inject_data_sub[_selected_rtcm_instance].update(&msg);

} while (updated && num_injections < max_num_injections);
}
Expand Down
66 changes: 49 additions & 17 deletions src/drivers/uavcan/sensors/gnss.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -467,29 +467,61 @@ void UavcanGnssBridge::update()
// to work.
void UavcanGnssBridge::handleInjectDataTopic()
{
// Limit maximum number of GPS injections to 6 since usually
// We don't want to call copy again further down if we have already done a
// copy in the selection process.
bool already_copied = false;
gps_inject_data_s msg;

// If there has not been a valid RTCM message for a while, try to switch to a different RTCM link
if ((hrt_absolute_time() - _last_rtcm_injection_time) > 5_s) {

for (int instance = 0; instance < _orb_inject_data_sub.size(); instance++) {
const bool exists = _orb_inject_data_sub[instance].advertised();

if (exists) {
if (_orb_inject_data_sub[instance].copy(&msg)) {
if ((hrt_absolute_time() - msg.timestamp) < 5_s) {
// Remember that we already did a copy on this instance.
already_copied = true;
_selected_rtcm_instance = instance;
break;
}
}
}
}
}

bool updated = already_copied;

// Limit maximum number of GPS injections to 8 since usually
// GPS injections should consist of 1-4 packets (GPS, Glonass, BeiDou, Galileo).
// Looking at 6 packets thus guarantees, that at least a full injection
// Looking at 8 packets thus guarantees, that at least a full injection
// data set is evaluated.
static constexpr size_t MAX_NUM_INJECTIONS = 6;

// Moving Base reuires a higher rate, so we allow up to 8 packets.
const size_t max_num_injections = gps_inject_data_s::ORB_QUEUE_LENGTH;
size_t num_injections = 0;
gps_inject_data_s gps_inject_data;

while ((num_injections <= MAX_NUM_INJECTIONS) && _gps_inject_data_sub.update(&gps_inject_data)) {
// Write the message to the gps device. Note that the message could be fragmented.
// But as we don't write anywhere else to the device during operation, we don't
// need to assemble the message first.
if (_publish_rtcm_stream) {
PublishRTCMStream(gps_inject_data.data, gps_inject_data.len);
}

if (_publish_moving_baseline_data) {
PublishMovingBaselineData(gps_inject_data.data, gps_inject_data.len);
do {
if (updated) {
num_injections++;

// Write the message to the gps device. Note that the message could be fragmented.
// But as we don't write anywhere else to the device during operation, we don't
// need to assemble the message first.
if (_publish_rtcm_stream) {
PublishRTCMStream(msg.data, msg.len);
}

if (_publish_moving_baseline_data) {
PublishMovingBaselineData(msg.data, msg.len);
}

_last_rtcm_injection_time = hrt_absolute_time();
}

num_injections++;
}
updated = _orb_inject_data_sub[_selected_rtcm_instance].update(&msg);

} while (updated && num_injections < max_num_injections);
}

bool UavcanGnssBridge::PublishRTCMStream(const uint8_t *const data, const size_t data_len)
Expand Down
5 changes: 4 additions & 1 deletion src/drivers/uavcan/sensors/gnss.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#pragma once

#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/sensor_gps.h>
#include <uORB/topics/gps_inject_data.h>
Expand Down Expand Up @@ -123,7 +124,9 @@ class UavcanGnssBridge : public UavcanSensorBridgeBase
float _last_gnss_auxiliary_hdop{0.0f};
float _last_gnss_auxiliary_vdop{0.0f};

uORB::Subscription _gps_inject_data_sub{ORB_ID(gps_inject_data)};
uORB::SubscriptionMultiArray<gps_inject_data_s, gps_inject_data_s::MAX_INSTANCES> _orb_inject_data_sub{ORB_ID::gps_inject_data};
hrt_abstime _last_rtcm_injection_time{0}; ///< time of last rtcm injection
uint8_t _selected_rtcm_instance{0}; ///< uorb instance that is being used for RTCM corrections

bool _system_clock_set{false}; ///< Have we set the system clock at least once from GNSS data?

Expand Down