GNSS: Don't send 'spoofing' warnings form driver (#25160)

* removing logic from driver to send warnings when state-change to spoofing is detected, handled in estimatorChecks

* also remove jamming warnings from drivers, those are handled in the estimator checks as well
This commit is contained in:
Marco Hauswirth 2025-07-07 09:44:26 +02:00 committed by GitHub
parent 588fd9d684
commit 6ee6a3a578
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
3 changed files with 0 additions and 43 deletions

View File

@ -1542,27 +1542,7 @@ void SeptentrioDriver::publish()
_message_gps_state.device_id = get_device_id();
_message_gps_state.selected_rtcm_instance = _selected_rtcm_instance;
_message_gps_state.rtcm_injection_rate = rtcm_injection_frequency();
_sensor_gps_pub.publish(_message_gps_state);
if (_message_gps_state.spoofing_state != _spoofing_state) {
if (_message_gps_state.spoofing_state > sensor_gps_s::SPOOFING_STATE_NONE) {
SEP_WARN("GPS spoofing detected! (state: %d)", _message_gps_state.spoofing_state);
}
_spoofing_state = _message_gps_state.spoofing_state;
}
if (_message_gps_state.jamming_state != _jamming_state) {
if (_message_gps_state.jamming_state > sensor_gps_s::JAMMING_STATE_WARNING) {
SEP_WARN("GPS jamming detected! (state: %d) (indicator: %d)", _message_gps_state.jamming_state,
(uint8_t)_message_gps_state.jamming_indicator);
}
_jamming_state = _message_gps_state.jamming_state;
}
}
void SeptentrioDriver::publish_satellite_info()

View File

@ -710,8 +710,6 @@ private:
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

View File

@ -190,8 +190,6 @@ private:
sensor_gps_s _report_gps_pos{}; ///< uORB topic for gps position
satellite_info_s *_p_report_sat_info{nullptr}; ///< pointer to uORB topic for satellite info
uint8_t _spoofing_state{0}; ///< spoofing state
uint8_t _jamming_state{0}; ///< jamming state
uORB::PublicationMulti<sensor_gps_s> _report_gps_pos_pub{ORB_ID(sensor_gps)}; ///< uORB pub for gps position
uORB::PublicationMulti<sensor_gnss_relative_s> _sensor_gnss_relative_pub{ORB_ID(sensor_gnss_relative)};
@ -1205,25 +1203,6 @@ GPS::publish()
// The uORB message definition requires this data to be set to a NAN if no new valid data is available.
_report_gps_pos.heading = NAN;
_is_gps_main_advertised.store(true);
if (_report_gps_pos.spoofing_state != _spoofing_state) {
if (_report_gps_pos.spoofing_state > sensor_gps_s::SPOOFING_STATE_NONE) {
PX4_WARN("GPS spoofing detected! (state: %d)", _report_gps_pos.spoofing_state);
}
_spoofing_state = _report_gps_pos.spoofing_state;
}
if (_report_gps_pos.jamming_state != _jamming_state) {
if (_report_gps_pos.jamming_state > sensor_gps_s::JAMMING_STATE_WARNING) {
PX4_WARN("GPS jamming detected! (state: %d) (indicator: %d)", _report_gps_pos.jamming_state,
(uint8_t)_report_gps_pos.jamming_indicator);
}
_jamming_state = _report_gps_pos.jamming_state;
}
}
}