You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When PX4 is connected to a NMEA GPS unit (UM980 in my case) the GPS status reports a rate of 0 B/s and an update rate of 0hz.
Typical output shown above.
To Reproduce
connect a NMEA GPS to a serial port and configure it as a GPS.
Run gps status and examine the results:
Connect the drone to a NEMA GPS. Run gps status.
nsh> gps status
INFO [gps] Main GPS
INFO [gps] protocol: NMEA
INFO [gps] status: OK, port: /dev/ttyS5, baudrate: 921600
INFO [gps] sat info: enabled
INFO [gps] rate reading: 0 B/s
INFO [gps] rate position: 0.00 Hz
INFO [gps] rate velocity: 0.00 Hz
INFO [gps] rate publication: 0.00 Hz
INFO [gps] rate RTCM injection: 0.00 Hz
sensor_gps
timestamp: 1166797117 (0.077381 seconds ago)
timestamp_sample: 0
Expected behavior
I have already developed a patch, although I have identified some additional issues with the GPS code, This is the result from the patched code.
nsh> gps status
INFO [gps] Main GPS
INFO [gps] protocol: NMEA
INFO [gps] status: OK, port: /dev/ttyS5, baudrate: 921600
INFO [gps] sat info: enabled
INFO [gps] rate reading: 3299 B/s
INFO [gps] rate position: 5.00 Hz
INFO [gps] rate velocity: 2.00 Hz
INFO [gps] rate publication: 6.79 Hz
INFO [gps] rate RTCM injection: 0.00 Hz
sensor_gps
timestamp: 34211212 (0.029154 seconds ago)
I haven't yet figured out how to submit a patch, but this issue is fixed with the following:
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index dff88ecbdc..9a6825f95b 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -475,6 +475,9 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
if (_interface == GPSHelper::Interface::UART) {
ret = _uart.readAtLeast(buf, buf_length, math::min(character_count, buf_length), timeout_adjusted);
+ if (ret > 0) {
+ _num_bytes_read += ret;
+ }
// SPI is only supported on LInux
#if defined(__PX4_LINUX)
diff --git a/src/nmea.cpp b/src/nmea.cpp
index a330c9a..3941bd5 100644
--- a/src/nmea.cpp
+++ b/src/nmea.cpp
@@ -853,13 +853,19 @@ int GPSDriverNMEA::handleMessage(int len)
_gps_position->satellites_used = MAX(_sat_num_gns, _sat_num_gsv);
}
- if (_VEL_received && _POS_received) {
+ /** update the stats for the velocity. */
+ if (_VEL_received) {
+ ret = 1;
+ _VEL_received = false;
+ _rate_count_vel++;
+ }
+
+ /** update the stats for the velocity. lat/long is considered to be a gps position update whereas velocity may not be */
+ if (_POS_received) {
ret = 1;
_gps_position->timestamp_time_relative = (int32_t)(_last_timestamp_time - _gps_position->timestamp);
_clock_set = false;
- _VEL_received = false;
_POS_received = false;
- _rate_count_vel++;
_rate_count_lat_lon++;
}
Screenshot / Media
No response
Flight Log
No response
Software Version
I'm running PX4 v 1.15.1 on a CubePilot Orange
Flight controller
No response
Vehicle type
Multicopter
How are the different components wired up (including port information)
No response
Additional context
No response
The text was updated successfully, but these errors were encountered:
Describe the bug
When PX4 is connected to a NMEA GPS unit (UM980 in my case) the GPS status reports a rate of 0 B/s and an update rate of 0hz.
Typical output shown above.
To Reproduce
connect a NMEA GPS to a serial port and configure it as a GPS.
Run gps status and examine the results:
Connect the drone to a NEMA GPS. Run gps status.
nsh> gps status
Expected behavior
I have already developed a patch, although I have identified some additional issues with the GPS code, This is the result from the patched code.
I haven't yet figured out how to submit a patch, but this issue is fixed with the following:
Screenshot / Media
No response
Flight Log
No response
Software Version
I'm running PX4 v 1.15.1 on a CubePilot Orange
Flight controller
No response
Vehicle type
Multicopter
How are the different components wired up (including port information)
No response
Additional context
No response
The text was updated successfully, but these errors were encountered: