Skip to content
Merged
Show file tree
Hide file tree
Changes from 32 commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
b86cd20
Initial PR
Louis-max-H Jun 3, 2025
72f330d
rebase with main
Louis-max-H Jun 16, 2025
1e47499
Fix uavcan gps sensor NAN for quality fields
Louis-max-H Jun 18, 2025
d1c5a0d
Update following community advices
Louis-max-H Jun 25, 2025
8bdfb1f
Update defaults values
Louis-max-H Jun 25, 2025
e896905
Add GpsStatus and update GNSS_INTEGRITY.hpp
Louis-max-H Jul 1, 2025
67b544b
Restore default mavlink module and board config
Louis-max-H Jul 2, 2025
a491864
use gnss instead of gps and improve sensor_gnss_status msg
Louis-max-H Jul 4, 2025
2005816
Merge branch 'main' into pr-resillience2
Louis-max-H Jul 4, 2025
e3e2442
Merge branch 'main' into pr-resillience2
Louis-max-H Jul 9, 2025
d2c5070
Fix merge conflict
Louis-max-H Jul 10, 2025
1a26610
Revert /docs to original state from main
Tory9 Jul 17, 2025
b8e221e
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Jul 17, 2025
c340690
Merge branch 'main' into pr-resillience2
mrpollo Jul 18, 2025
b73dc8c
uint32_t fix
Tory9 Jul 20, 2025
9ea56ec
Merge branch 'main' into pr-resillience2
Tory9 Jul 20, 2025
71544ec
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Jul 30, 2025
7ba494d
compiler error fixed
Tory9 Jul 30, 2025
838b5e6
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Jul 30, 2025
af6e9ed
inconsistency fixed
Tory9 Jul 30, 2025
487fd9f
InfoMode error fix
Tory9 Jul 30, 2025
df09e66
update PX4-GPSDrivers to include cfg_wipe
Tory9 Jul 30, 2025
daeb1e8
compiler error fixed
Tory9 Jul 30, 2025
b95da27
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Aug 5, 2025
8da7fff
Apply suggestion from @dagar
Tory9 Aug 21, 2025
97a5a35
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Aug 22, 2025
7dc69f0
suggestions from dagar considered and check on data being recent mov…
Tory9 Aug 28, 2025
46c9a74
cleanup
Tory9 Aug 29, 2025
8dc7fb5
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Aug 29, 2025
499ef9b
Merge remote-tracking branch 'upstream/main' into pr-resillience2
Tory9 Sep 3, 2025
b45902e
mavlink suggestions from dagar applied
Tory9 Sep 4, 2025
a73101d
timeout changed to 3s
Tory9 Sep 5, 2025
7758022
Update boards/cubepilot/cubeorangeplus/default.px4board
dagar Sep 10, 2025
2663ed1
Merge branch 'main' into pr-resillience2
dagar Sep 17, 2025
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
1 change: 1 addition & 0 deletions boards/cubepilot/cubeorangeplus/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -95,3 +95,4 @@ CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_MAVLINK_DIALECT="development"
1 change: 1 addition & 0 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,7 @@ set(msg_files
SensorCombined.msg
SensorCorrection.msg
SensorGnssRelative.msg
SensorGnssStatus.msg
SensorGps.msg
SensorGyro.msg
SensorGyroFft.msg
Expand Down
10 changes: 10 additions & 0 deletions msg/SensorGnssStatus.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# Gnss quality indicators

uint64 timestamp # time since system start (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
Copy link
Member

Choose a reason for hiding this comment

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

Make sure you populate the device_id everywhere, that's how we'll know with GNSS a particular sensor_gnss_status topic corresponds with (if there's more than 1).

Copy link
Contributor

Choose a reason for hiding this comment

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

The device_id for the sensor_gnss_status message is populated within the process_message() function, specifically in the case BlockID::QualityInd: block.
This is the only location where the _message_sensor_gnss_status struct is populated, and the device_id is set immediately ( line1231 ) before the message is published. So it should be fine


bool quality_available # Set to true if quality indicators are available
uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available
Copy link
Member

Choose a reason for hiding this comment

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

Are all of these fields simply 0-10 with no specific meaning?

Unless the integer values are actually meaning can we publish them as a percentage in a float? That will be a bit more self explanatory from a log review standpoint.

Copy link
Contributor

Choose a reason for hiding this comment

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

The value represents a quality score where 0 indicates poor quality and 10 indicates excellent quality. We use an integer score instead of a percentage because a percentage could be misleading, implying something is "incomplete", this is aalso a common practice in other applications/daily life to rate smth not in percentages but based on the scale. Also such scoring keeps it consistent with the Septentrio web tool, which is familiar to most users of this receiver. But we can further discuss this

uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available
uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available
uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available
42 changes: 30 additions & 12 deletions msg/SensorGps.msg
Original file line number Diff line number Diff line change
Expand Up @@ -30,18 +30,26 @@ float32 vdop # Vertical dilution of precision
int32 noise_per_ms # GPS noise per millisecond
uint16 automatic_gain_control # Automatic gain control monitor

uint8 JAMMING_STATE_UNKNOWN = 0
uint8 JAMMING_STATE_OK = 1
uint8 JAMMING_STATE_WARNING = 2
uint8 JAMMING_STATE_CRITICAL = 3
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
int32 jamming_indicator # indicates jamming is occurring

uint8 SPOOFING_STATE_UNKNOWN = 0
uint8 SPOOFING_STATE_NONE = 1
uint8 SPOOFING_STATE_INDICATED = 2
uint8 SPOOFING_STATE_MULTIPLE = 3
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical
uint8 JAMMING_STATE_UNKNOWN = 0 #default
uint8 JAMMING_STATE_OK = 1
uint8 JAMMING_STATE_MITIGATED = 2
uint8 JAMMING_STATE_DETECTED = 3
uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected
int32 jamming_indicator # indicates jamming is occurring

uint8 SPOOFING_STATE_UNKNOWN = 0 #default
uint8 SPOOFING_STATE_OK = 1
uint8 SPOOFING_STATE_MITIGATED = 2
uint8 SPOOFING_STATE_DETECTED = 3
uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected

# Combined authentication state (e.g. Galileo OSNMA)
uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default
uint8 AUTHENTICATION_STATE_INITIALIZING = 1
uint8 AUTHENTICATION_STATE_ERROR = 2
uint8 AUTHENTICATION_STATE_OK = 3
uint8 AUTHENTICATION_STATE_DISABLED = 4
uint8 authentication_state # GPS signal authentication state
Copy link
Member

Choose a reason for hiding this comment

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

I'm not exactly sure where the line is between sensor_gps and sensor_gnss_status, but as a start can you place all of these "status" fields into sensor_gnss_status as well?

Copy link
Contributor

Choose a reason for hiding this comment

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

The separation of the topics was based on the original SBF messages and a logical split between critical and non-critical data.

The principle is to keep sensor_gps for essential, high-frequency parameters like position, system errors, and resilience data. In contrast, sensor_gnss_status is intended for more general, informative data that is less critical and does not require such frequent updates.

This design keeps the primary sensor_gps topic cleaner. It also makes sensor_gnss_status a flexible place to add more informational parameters in the future without overloading the main topic


float32 vel_m_s # GPS ground speed, (metres/sec)
float32 vel_n_m_s # GPS North velocity, (metres/sec)
Expand All @@ -55,6 +63,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi

uint8 satellites_used # Number of satellites used

uint32 SYSTEM_ERROR_OK = 0 #default
uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1
uint32 SYSTEM_ERROR_CONFIGURATION = 2
uint32 SYSTEM_ERROR_SOFTWARE = 4
uint32 SYSTEM_ERROR_ANTENNA = 8
uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16
uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32
uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64
uint32 system_error # General errors with the connected GPS receiver
Copy link
Member

Choose a reason for hiding this comment

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

Seems like a good one for gnss status as well.


float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI])
float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI])
float32 heading_accuracy # heading accuracy (rad, [0, 2PI])
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/gnss/septentrio/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ px4_add_module(
COMPILE_FLAGS
# -DDEBUG_BUILD # Enable during development of the module
-DSEP_LOG_ERROR # Enable module-level error logs
# -DSEP_LOG_WARN # Enable module-level warning logs
-DSEP_LOG_WARN # Enable module-level warning logs
# -DSEP_LOG_INFO # Enable module-level info logs
# -DSEP_LOG_TRACE_PARSING # Tracing of parsing steps
SRCS
Expand Down
2 changes: 1 addition & 1 deletion src/drivers/gnss/septentrio/sbf/decoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ int Decoder::parse(QualityInd *message) const

int Decoder::parse(RFStatus *message) const
{
if (can_parse() && id() == BlockID::PVTGeodetic) {
if (can_parse() && id() == BlockID::RFStatus) {
static_assert(sizeof(*message) <= sizeof(_message.payload), "Buffer too small");
memcpy(message, _message.payload, sizeof(RFStatus) - sizeof(RFStatus::rf_band));

Expand Down
18 changes: 17 additions & 1 deletion src/drivers/gnss/septentrio/sbf/messages.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,9 +243,14 @@ struct QualityInd {
};

struct RFBand {
enum class InfoMode : uint8_t {
Suppressed = 1,
Mitigated = 2,
Interference = 8
};
uint32_t frequency;
uint16_t bandwidth;
uint8_t info_mode: 4;
uint8_t info_mode: 4;
uint8_t info_reserved: 2;
uint8_t info_antenna_id: 2;
};
Expand All @@ -261,6 +266,15 @@ struct RFStatus {
};

struct GALAuthStatus {
enum class OSNMAStatus : uint16_t {
Disabled = 0,
Initializing = 1,
AwaitingTrustedTimeInfo = 2,
InitFailedInconsistentTime = 3,
InitFailedKROOTInvalid = 4,
InitFailedInvalidParam = 5,
Authenticating = 6,
};
uint16_t osnma_status_status: 3;
uint16_t osnma_status_initialization_progress: 8;
uint16_t osnma_status_trusted_time_source: 3;
Expand All @@ -271,6 +285,8 @@ struct GALAuthStatus {
uint64_t gal_authentic_mask;
uint64_t gps_active_mask;
uint64_t gps_authentic_mask;

OSNMAStatus osnmaStatus() const { return static_cast<OSNMAStatus>(osnma_status_status); }
};

struct VelCovGeodetic {
Expand Down
150 changes: 147 additions & 3 deletions src/drivers/gnss/septentrio/septentrio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ constexpr size_t k_min_receiver_read_bytes = 32;
*/
constexpr uint32_t k_septentrio_receiver_default_baud_rate = 115200;

constexpr uint8_t k_max_command_size = 120;
constexpr uint8_t k_max_command_size = 140;
constexpr uint16_t k_timeout_5hz = 500;
constexpr uint32_t k_read_buffer_size = 150;
constexpr time_t k_gps_epoch_secs = 1234567890ULL; // TODO: This seems wrong
Expand All @@ -112,7 +112,7 @@ constexpr const char *k_command_reset_hot = "erst,soft,none\n";
constexpr const char *k_command_reset_warm = "erst,soft,PVTData\n";
constexpr const char *k_command_reset_cold = "erst,hard,SatData\n";
constexpr const char *k_command_sbf_output_pvt =
"sso,Stream%" PRIu32 ",%s,PVTGeodetic+VelCovGeodetic+DOP+AttEuler+AttCovEuler+EndOfPVT+ReceiverStatus,%s\n";
"sso,Stream%lu,%s,PVTGeodetic+VelCovGeodetic+DOP+AttEuler+AttCovEuler+EndOfPVT+ReceiverStatus+GALAuthStatus+RFStatus+QualityInd,%s\n";
constexpr const char *k_command_set_sbf_output =
"sso,Stream%" PRIu32 ",%s,%s%s,%s\n";
constexpr const char *k_command_clear_sbf = "sso,Stream%" PRIu32 ",%s,none,off\n";
Expand Down Expand Up @@ -967,7 +967,7 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure()
}

// Output a set of SBF blocks on a given connection at a regular interval.
snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency);
snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, (long unsigned int) _receiver_stream_main, com_port, sbf_frequency);
if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) {
SEP_WARN("CONFIG: Failed to configure SBF");
return ConfigureResult::FailedCompletely;
Expand Down Expand Up @@ -1191,20 +1191,138 @@ int SeptentrioDriver::process_message()
if (_sbf_decoder.parse(&receiver_status) == PX4_OK) {
_sensor_gps.rtcm_msg_used = receiver_status.rx_state_diff_corr_in ? sensor_gps_s::RTCM_MSG_USED_USED : sensor_gps_s::RTCM_MSG_USED_NOT_USED;
_time_synced = receiver_status.rx_state_wn_set && receiver_status.rx_state_tow_set;

_sensor_gps.system_error = sensor_gps_s::SYSTEM_ERROR_OK;

if (receiver_status.rx_error_cpu_overload) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_CPU_OVERLOAD;
}
if (receiver_status.rx_error_antenna) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_ANTENNA;
}
if (receiver_status.ext_error_diff_corr_error) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_INCOMING_CORRECTIONS;
}
if (receiver_status.ext_error_setup_error) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_CONFIGURATION;
}
if (receiver_status.rx_error_software) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_SOFTWARE;
}
if (receiver_status.rx_error_congestion) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_OUTPUT_CONGESTION;
}
if (receiver_status.rx_error_missed_event) {
_sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_EVENT_CONGESTION;
}
}

break;
}
case BlockID::QualityInd: {
using Type = QualityIndicator::Type;

SEP_TRACE_PARSING("Processing QualityInd SBF message");

QualityInd quality_ind;

if (_sbf_decoder.parse(&quality_ind) == PX4_OK) {
_message_sensor_gnss_status.quality_available = true;
_message_sensor_gnss_status.device_id = get_device_id();

_message_sensor_gnss_status.quality_corrections = 255;
_message_sensor_gnss_status.quality_receiver = 255;
_message_sensor_gnss_status.quality_post_processing = 255;
_message_sensor_gnss_status.quality_gnss_signals = 255;

for (int i = 0; i < math::min(quality_ind.n, static_cast<uint8_t>(sizeof(quality_ind.indicators) / sizeof(quality_ind.indicators[0]))); i++) {
int quality = quality_ind.indicators[i].value;

switch (quality_ind.indicators[i].type) {
case Type::BaseStationMeasurements:
_message_sensor_gnss_status.quality_corrections = quality;
break;
case Type::Overall:
_message_sensor_gnss_status.quality_receiver = quality;
break;
case Type::RTKPostProcessing:
_message_sensor_gnss_status.quality_post_processing = quality;
break;
case Type::GNSSSignalsMainAntenna:
_message_sensor_gnss_status.quality_gnss_signals = quality;
break;
default:
break;
}
}


_message_sensor_gnss_status.timestamp = hrt_absolute_time();
_time_last_qualityind_received = hrt_absolute_time();
_sensor_gnss_status_pub.publish(_message_sensor_gnss_status);
}

break;
}
case BlockID::RFStatus: {
using InfoMode = RFBand::InfoMode;

SEP_TRACE_PARSING("Processing RFStatus SBF message");

RFStatus rf_status;

if (_sbf_decoder.parse(&rf_status) == PX4_OK) {
_sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_OK;
_sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_OK;

for (int i = 0; i < math::min(rf_status.n, static_cast<uint8_t>(sizeof(rf_status.rf_band) / sizeof(rf_status.rf_band[0]))); i++) {
InfoMode status = static_cast<InfoMode>(rf_status.rf_band[i].info_mode);

if(status == InfoMode::Interference){
_sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_DETECTED;
break; // Worst case, we don't need to check the other bands
}

if(status == InfoMode::Suppressed || status == InfoMode::Mitigated){
_sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_MITIGATED;
}
}

if (rf_status.flags_inauthentic_gnss_signals || rf_status.flags_inauthentic_navigation_message) {
_sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_DETECTED;
}
_time_last_resilience_received = hrt_absolute_time();
}

break;
}
case BlockID::GALAuthStatus: {
using OSNMAStatus = GALAuthStatus::OSNMAStatus;

SEP_TRACE_PARSING("Processing GALAuthStatus SBF message");

GALAuthStatus gal_auth_status;

if (_sbf_decoder.parse(&gal_auth_status) == PX4_OK) {
switch (gal_auth_status.osnmaStatus()) {
case OSNMAStatus::Disabled:
_sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_DISABLED;
break;
case OSNMAStatus::AwaitingTrustedTimeInfo:
case OSNMAStatus::Initializing:
_sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_INITIALIZING;
break;
case OSNMAStatus::InitFailedInconsistentTime:
case OSNMAStatus::InitFailedKROOTInvalid:
case OSNMAStatus::InitFailedInvalidParam:
_sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_ERROR;
break;
case OSNMAStatus::Authenticating:
_sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_OK;
break;
}
}

break;
}
case BlockID::EndOfPVT: {
Expand Down Expand Up @@ -1277,6 +1395,31 @@ int SeptentrioDriver::process_message()
}
}

//Check for how recent the resilience data for reciever is, if outdated set to unknown
if ((_time_last_resilience_received != 0) && (hrt_elapsed_time(&_time_last_resilience_received) > 5_s)) {
_sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_UNKNOWN;
_sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_UNKNOWN;

_time_last_resilience_received = 0; // Reset
}

// Check for how recent the status data for receiver is, if outdated set to unknown
if ((_time_last_qualityind_received != 0) && (hrt_elapsed_time(&_time_last_qualityind_received) > 5_s)) {
_message_sensor_gnss_status.quality_available = false;
_message_sensor_gnss_status.device_id = get_device_id();
_message_sensor_gnss_status.timestamp = hrt_absolute_time();

_message_sensor_gnss_status.quality_corrections = 255;
_message_sensor_gnss_status.quality_receiver = 255;
_message_sensor_gnss_status.quality_post_processing = 255;
_message_sensor_gnss_status.quality_gnss_signals = 255;


_sensor_gnss_status_pub.publish(_message_sensor_gnss_status);

_time_last_qualityind_received = 0; // Reset
}

break;
}
case DecodingStatus::RTCMv3: {
Expand Down Expand Up @@ -1532,6 +1675,7 @@ void SeptentrioDriver::publish()
_sensor_gps.device_id = get_device_id();
_sensor_gps.selected_rtcm_instance = _selected_rtcm_instance;
_sensor_gps.rtcm_injection_rate = rtcm_injection_frequency();
_sensor_gps.timestamp = hrt_absolute_time();
_sensor_gps_pub.publish(_sensor_gps);
}

Expand Down
23 changes: 15 additions & 8 deletions src/drivers/gnss/septentrio/septentrio.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/satellite_info.h>
#include <uORB/topics/sensor_gps.h>
#include <uORB/topics/sensor_gnss_status.h>
#include <uORB/topics/gps_dump.h>
#include <uORB/topics/gps_inject_data.h>
#include <drivers/drv_hrt.h>
Expand Down Expand Up @@ -710,12 +711,16 @@ class SeptentrioDriver : public ModuleBase<SeptentrioDriver>, public device::Dev
char _port[20] {}; ///< The path of the used serial device
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
uint8_t _spoofing_state {0}; ///< Receiver spoofing state
uint8_t _jamming_state {0}; ///< Receiver jamming state
bool _time_synced {false}; ///< Receiver time in sync with GPS time
const Instance _instance {Instance::Main}; ///< The receiver that this instance of the driver controls
uint32_t _chosen_baud_rate {0}; ///< The baud rate requested by the user
static px4::atomic<SeptentrioDriver *> _secondary_instance;
hrt_abstime _sleep_end {0}; ///< End time for sleeping
State _resume_state {State::OpeningSerialPort}; ///< Resume state after sleep
hrt_abstime _time_last_qualityind_received{0}; ///< Time of last quality message reception
hrt_abstime _time_last_resilience_received{0}; ///< Time of last resilience message reception

// Module configuration
float _heading_offset {0.0f}; ///< The heading offset given by the `SEP_YAW_OFFS` parameter
Expand All @@ -737,14 +742,16 @@ class SeptentrioDriver : public ModuleBase<SeptentrioDriver>, public device::Dev
rtcm::Decoder *_rtcm_decoder {nullptr}; ///< RTCM message decoder

// uORB topics and subscriptions
sensor_gps_s _sensor_gps{}; ///< uORB topic for position
gps_dump_s *_message_data_to_receiver {nullptr}; ///< uORB topic for dumping data to the receiver
gps_dump_s *_message_data_from_receiver {nullptr}; ///< uORB topic for dumping data from the receiver
satellite_info_s *_message_satellite_info {nullptr}; ///< uORB topic for satellite info
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub {ORB_ID(sensor_gps)}; ///< uORB publication for gps position
uORB::Publication<gps_dump_s> _gps_dump_pub {ORB_ID(gps_dump)}; ///< uORB publication for dump GPS data
uORB::Publication<gps_inject_data_s> _gps_inject_data_pub {ORB_ID(gps_inject_data)}; ///< uORB publication for injected data to the receiver
uORB::PublicationMulti<satellite_info_s> _satellite_info_pub {ORB_ID(satellite_info)}; ///< uORB publication for satellite info
sensor_gps_s _sensor_gps {}; ///< uORB topic for position
sensor_gnss_status_s _message_sensor_gnss_status {}; ///< uORB topic for gps status
gps_dump_s *_message_data_to_receiver {nullptr}; ///< uORB topic for dumping data to the receiver
gps_dump_s *_message_data_from_receiver {nullptr}; ///< uORB topic for dumping data from the receiver
satellite_info_s *_message_satellite_info {nullptr}; ///< uORB topic for satellite info
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub {ORB_ID(sensor_gps)}; ///< uORB publication for gps position
uORB::PublicationMulti<sensor_gnss_status_s> _sensor_gnss_status_pub {ORB_ID(sensor_gnss_status)}; ///< uORB publication for gnss status
uORB::Publication<gps_dump_s> _gps_dump_pub {ORB_ID(gps_dump)}; ///< uORB publication for dump GPS data
uORB::Publication<gps_inject_data_s> _gps_inject_data_pub {ORB_ID(gps_inject_data)}; ///< uORB publication for injected data to the receiver
uORB::PublicationMulti<satellite_info_s> _satellite_info_pub {ORB_ID(satellite_info)}; ///< uORB publication for satellite info
uORB::SubscriptionMultiArray<gps_inject_data_s, gps_inject_data_s::MAX_INSTANCES> _gps_inject_data_sub {ORB_ID::gps_inject_data}; ///< uORB subscription about data to inject to the receiver

// Data about update frequencies of various bits of information like RTCM message injection frequency, received data rate...
Expand Down
Loading
Loading