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

Add detected message when GPS found #26257

Merged
merged 4 commits into from
Feb 20, 2024
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: 11 additions & 7 deletions Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -13509,11 +13509,11 @@ def GPSTypes(self):
# if gps_type is None we auto-detect
sim_gps = [
# (0, "NONE"),
(1, "UBLOX", None, "u-blox", 5, 'detected'),
(5, "NMEA", 5, "NMEA", 5, 'detected'),
(6, "SBP", None, "SBP", 5, 'detected'),
(1, "UBLOX", None, "u-blox", 5, 'probing'),
(5, "NMEA", 5, "NMEA", 5, 'probing'),
(6, "SBP", None, "SBP", 5, 'probing'),
# (7, "SBP2", 9, "SBP2", 5), # broken, "waiting for config data"
(8, "NOVA", 15, "NOVA", 5, 'detected'), # no attempt to auto-detect this in AP_GPS
(8, "NOVA", 15, "NOVA", 5, 'probing'), # no attempt to auto-detect this in AP_GPS
(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS
(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS
# (9, "FILE"),
Expand All @@ -13528,7 +13528,11 @@ def GPSTypes(self):
self.set_parameter("GPS_TYPE", gps_type)
self.context_clear_collection('STATUSTEXT')
self.reboot_sitl()
self.wait_statustext("%s as %s" % (detect_prefix, detect_name), check_context=True)
if detect_prefix == "probing":
self.wait_statustext(f"probing for {detect_name}", check_context=True)
else:
self.wait_statustext(f"specified as {detect_name}", check_context=True)
self.wait_statustext(f"detected {detect_name}", check_context=True)
n = self.poll_home_position(timeout=120)
distance = self.get_distance_int(orig, n)
if distance > 1:
Expand Down Expand Up @@ -13565,8 +13569,8 @@ def MultipleGPS(self):
# AP_GPS::init() at boot time, so it will never be detected.
self.context_collect("STATUSTEXT")
self.reboot_sitl()
self.wait_statustext("GPS 1: detected as u-blox", check_context=True)
self.wait_statustext("GPS 2: detected as u-blox", check_context=True)
self.wait_statustext("GPS 1: detected u-blox", check_context=True)
self.wait_statustext("GPS 2: detected u-blox", check_context=True)
m = self.assert_receive_message("GPS2_RAW")
self.progress(self.dump_message_verbose(m))
# would be nice for it to take some time to get a fix....
Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -999,6 +999,14 @@ void AP_GPS::update_instance(uint8_t instance)
tnow = state[instance].last_corrected_gps_time_us/1000U;
state[instance].corrected_timestamp_updated = false;
}

// we set delta_time_ms to the timeout value when clearing
// state; use it being zero to mark first message
if (!state[instance].announced_detection) {
state[instance].announced_detection = true;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GPS %d: detected %s", instance + 1, drivers[instance]->name());
}

// delta will only be correct after parsing two messages
timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
timing[instance].last_message_time_ms = tnow;
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -212,6 +212,7 @@ class AP_GPS
float undulation; //<height that WGS84 is above AMSL at the current location
bool have_undulation; ///<do we have a value for the undulation
uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
bool announced_detection; ///< true once we have announced GPS has been seen to the user
uint64_t last_corrected_gps_time_us;///< the system time we got the last corrected GPS timestamp, microseconds
bool corrected_timestamp_updated; ///< true if the corrected timestamp has been updated
uint32_t lagged_sample_count; ///< number of samples with 50ms more lag than expected
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/GPS_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) cons

if (dstate.auto_detected_baud) {
hal.util->snprintf(buffer, buflen,
"GPS %d: detected as %s at %d baud",
"GPS %d: probing for %s at %d baud",
instance + 1,
name(),
int(gps._baudrates[dstate.current_baud]));
Expand Down
5 changes: 5 additions & 0 deletions libraries/SITL/SIM_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@
#include "SIM_GPS_SBP.h"
#include "SIM_GPS_UBLOX.h"

#include <GCS_MAVLink/GCS.h>

// the number of GPS leap seconds - copied from AP_GPS.h
#define GPS_LEAPSECONDS_MILLIS 18000ULL

Expand Down Expand Up @@ -279,6 +281,9 @@ void GPS::check_backend_allocation()
#endif
};

if (configured_type != Type::NONE && backend == nullptr) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_GPS: No backend for %u", (unsigned)configured_type);
}
allocated_type = configured_type;
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -499,7 +499,7 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Param: GPS_TYPE
// @DisplayName: GPS 1 type
// @Description: Sets the type of simulation used for GPS 1
// @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:Trimble, 19:MSP
// @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP2, 11:Trimble, 19:MSP
Copy link
Contributor

Choose a reason for hiding this comment

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

isn't trimble a SBF type ? so we that would be 10 ? @Ryanf55

Copy link
Collaborator

Choose a reason for hiding this comment

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

No, Trimble PX1 uses GSOF as a protocol and has no affiliation with SBF.

Copy link
Contributor

Choose a reason for hiding this comment

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

Ok so some comment on ap_gps are misleading then as they said sbf and trimble are similar

// @User: Advanced
AP_GROUPINFO("GPS_TYPE", 3, SIM, gps_type[0], GPS::Type::UBLOX),
// @Param: GPS_BYTELOSS
Expand Down
Loading