mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 13:02:25 +08:00
Add GPS spoofing state
This commit is contained in:
@@ -30,6 +30,12 @@ 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
|
||||
|
||||
float32 vel_m_s # GPS ground speed, (metres/sec)
|
||||
float32 vel_n_m_s # GPS North velocity, (metres/sec)
|
||||
float32 vel_e_m_s # GPS East velocity, (metres/sec)
|
||||
|
||||
@@ -40,6 +40,7 @@ px4_add_module(
|
||||
-Wno-stringop-overflow # due to https://gcc.gnu.org/bugzilla/show_bug.cgi?id=91707
|
||||
SRCS
|
||||
gps.cpp
|
||||
devices/src/crc.cpp
|
||||
devices/src/gps_helper.cpp
|
||||
devices/src/mtk.cpp
|
||||
devices/src/ashtech.cpp
|
||||
@@ -48,6 +49,7 @@ px4_add_module(
|
||||
devices/src/emlid_reach.cpp
|
||||
devices/src/femtomes.cpp
|
||||
devices/src/nmea.cpp
|
||||
devices/src/unicore.cpp
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
|
||||
+1
-1
Submodule src/drivers/gps/devices updated: 5882667129...33e447a3ba
@@ -182,6 +182,8 @@ 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)};
|
||||
@@ -1194,6 +1196,25 @@ 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_OK) {
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -82,6 +82,7 @@ void FakeGps::Run()
|
||||
sensor_gps.heading_offset = 0.0000;
|
||||
sensor_gps.fix_type = 4;
|
||||
sensor_gps.jamming_state = 0;
|
||||
sensor_gps.spoofing_state = 0;
|
||||
sensor_gps.vel_ned_valid = true;
|
||||
sensor_gps.satellites_used = 14;
|
||||
sensor_gps.timestamp = hrt_absolute_time();
|
||||
|
||||
@@ -670,6 +670,29 @@ void EstimatorChecks::checkGps(const Context &context, Report &reporter, const s
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "GPS reports critical jamming state\t");
|
||||
}
|
||||
}
|
||||
|
||||
if (vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_INDICATED) {
|
||||
/* EVENT
|
||||
*/
|
||||
reporter.armingCheckFailure(NavModes::None, health_component_t::gps,
|
||||
events::ID("check_estimator_gps_spoofing_indicated"),
|
||||
events::Log::Critical, "GPS reports spoofing indicated");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "GPS reports spoofing indicated\t");
|
||||
}
|
||||
|
||||
} else if (vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_MULTIPLE) {
|
||||
/* EVENT
|
||||
*/
|
||||
reporter.armingCheckFailure(NavModes::None, health_component_t::gps,
|
||||
events::ID("check_estimator_gps_multiple_spoofing_indicated"),
|
||||
events::Log::Critical, "GPS reports multiple spoofing indicated");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "GPS reports multiple spoofing indicated\t");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &reporter,
|
||||
|
||||
@@ -2449,6 +2449,7 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
|
||||
gps.automatic_gain_control = 0;
|
||||
gps.jamming_indicator = 0;
|
||||
gps.jamming_state = 0;
|
||||
gps.spoofing_state = 0;
|
||||
|
||||
gps.vel_m_s = (float)(hil_gps.vel) / 100.0f; // cm/s -> m/s
|
||||
gps.vel_n_m_s = (float)(hil_gps.vn) / 100.0f; // cm/s -> m/s
|
||||
|
||||
@@ -171,6 +171,7 @@ void SensorGpsSim::Run()
|
||||
sensor_gps.heading_accuracy = 0;
|
||||
sensor_gps.automatic_gain_control = 0;
|
||||
sensor_gps.jamming_state = 0;
|
||||
sensor_gps.spoofing_state = 0;
|
||||
sensor_gps.vel_ned_valid = true;
|
||||
sensor_gps.satellites_used = _sim_gps_used.get();
|
||||
|
||||
|
||||
@@ -421,6 +421,7 @@ void SimulatorMavlink::handle_message_hil_gps(const mavlink_message_t *msg)
|
||||
gps.automatic_gain_control = 0;
|
||||
gps.jamming_indicator = 0;
|
||||
gps.jamming_state = 0;
|
||||
gps.spoofing_state = 0;
|
||||
|
||||
gps.vel_m_s = (float)(hil_gps.vel) / 100.0f; // cm/s -> m/s
|
||||
gps.vel_n_m_s = (float)(hil_gps.vn) / 100.0f; // cm/s -> m/s
|
||||
|
||||
Reference in New Issue
Block a user