I have had a bit of a dig through some source code and found the AP_NMEA_Output.cpp code that assembles the relevant strings. It seems to me that the code that formats the latitude (line 102), longitude (line 112) are not getting the right data coming in on loc.lat and loc.lng. The altitude data in loc.alt (line 132) is also zero. Also, from the data captured earlier in the thread, pos_valid is showing as 0, even though I am getting valid position data in MP via Mavlink.
AP_NMEA_Output.cpp
1 : /*
2 : This program is free software: you can redistribute it and/or modify
3 : it under the terms of the GNU General Public License as published by
4 : the Free Software Foundation, either version 3 of the License, or
5 : (at your option) any later version.
6 :
7 : This program is distributed in the hope that it will be useful,
8 : but WITHOUT ANY WARRANTY; without even the implied warranty of
9 : MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10 : GNU General Public License for more details.
11 :
12 : You should have received a copy of the GNU General Public License
13 : along with this program. If not, see <http://www.gnu.org/licenses/>.
14 :
15 :
16 : Author: Francisco Ferreira (some code is copied from sitl_gps.cpp)
17 :
18 : */
19 :
20 : #include "AP_NMEA_Output.h"
21 :
22 : #if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
23 :
24 : #include <AP_Math/definitions.h>
25 : #include <AP_RTC/AP_RTC.h>
26 : #include <AP_SerialManager/AP_SerialManager.h>
27 :
28 : #include <stdio.h>
29 : #include <time.h>
30 :
31 : AP_NMEA_Output* AP_NMEA_Output::_singleton;
32 :
33 1 : AP_NMEA_Output::AP_NMEA_Output()
34 : {
35 1 : AP_SerialManager& sm = AP::serialmanager();
36 :
37 2 : for (uint8_t i = 0; i < ARRAY_SIZE(_uart); i++) {
38 2 : _uart[i] = sm.find_serial(AP_SerialManager::SerialProtocol_NMEAOutput, i);
39 :
40 2 : if (_uart[i] == nullptr) {
41 1 : break;
42 : }
43 1 : _num_outputs++;
44 : }
45 1 : }
46 :
47 394 : AP_NMEA_Output* AP_NMEA_Output::probe()
48 : {
49 394 : if (!_singleton && AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_NMEAOutput, 0) != nullptr) {
50 1 : _singleton = new AP_NMEA_Output();
51 : }
52 :
53 394 : return _singleton;
54 : }
55 :
56 140 : uint8_t AP_NMEA_Output::_nmea_checksum(const char *str)
57 : {
58 140 : uint8_t checksum = 0;
59 140 : const uint8_t* bytes = (const uint8_t*) str;
60 :
61 9730 : for (uint16_t i = 1; str[i]; i++) {
62 9590 : checksum ^= bytes[i];
63 : }
64 :
65 140 : return checksum;
66 : }
67 :
68 691 : void AP_NMEA_Output::update()
69 : {
70 691 : const uint32_t now_ms = AP_HAL::millis();
71 :
72 : // only send at 10Hz
73 691 : if ((now_ms - _last_run_ms) < 100) {
74 621 : return;
75 : }
76 139 : _last_run_ms = now_ms;
77 :
78 : // get time and date
79 : uint64_t time_usec;
80 139 : if (!AP::rtc().get_utc_usec(time_usec)) {
81 69 : return;
82 : }
83 :
84 : // not completely accurate, our time includes leap seconds and time_t should be without
85 70 : const time_t time_sec = time_usec / 1000000;
86 70 : struct tm* tm = gmtime(&time_sec);
87 :
88 : // format time string
89 : char tstring[11];
90 70 : snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6);
91 :
92 : // format date string
93 : char dstring[7];
94 70 : snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100);
95 :
96 70 : AP_AHRS_NavEKF& ahrs = AP::ahrs_navekf();
97 :
98 : // get location (note: get_position from AHRS always returns true after having GPS position once)
99 70 : Location loc;
100 70 : bool pos_valid = ahrs.get_location(loc);
101 :
102 : // format latitude
103 : char lat_string[13];
104 70 : float deg = fabsf(loc.lat * 1.0e-7f);
105 70 : snprintf(lat_string,
106 : sizeof(lat_string),
107 : "%02u%08.5f,%c",
108 : (unsigned) deg,
109 70 : double((deg - int(deg)) * 60),
110 70 : loc.lat < 0 ? 'S' : 'N');
111 :
112 : // format longitude
113 : char lng_string[14];
114 70 : deg = fabsf(loc.lng * 1.0e-7f);
115 70 : snprintf(lng_string,
116 : sizeof(lng_string),
117 : "%03u%08.5f,%c",
118 : (unsigned) deg,
119 70 : double((deg - int(deg)) * 60),
120 70 : loc.lng < 0 ? 'W' : 'E');
121 :
122 : // format GGA message
123 70 : char* gga = nullptr;
124 70 : int16_t gga_res = asprintf(&gga,
125 : "$GPGGA,%s,%s,%s,%01d,%02d,%04.1f,%07.2f,M,0.0,M,,",
126 : tstring,
127 : lat_string,
128 : lng_string,
129 : pos_valid ? 1 : 0,
130 : pos_valid ? 6 : 3,
131 : 2.0,
132 70 : loc.alt * 0.01f);
133 70 : if (gga_res == -1) {
134 0 : return;
135 : }
136 : char gga_end[6];
137 70 : snprintf(gga_end, sizeof(gga_end), "*%02X\r\n", (unsigned) _nmea_checksum(gga));
138 :
139 : // get speed
140 70 : Vector2f speed = ahrs.groundspeed_vector();
141 70 : float speed_knots = norm(speed.x, speed.y) * M_PER_SEC_TO_KNOTS;
142 70 : float heading = wrap_360(degrees(atan2f(speed.x, speed.y)));
143 :
144 : // format RMC message
145 70 : char* rmc = nullptr;
146 70 : int16_t rmc_res = asprintf(&rmc,
147 : "$GPRMC,%s,%c,%s,%s,%.2f,%.2f,%s,,",
148 : tstring,
149 : pos_valid ? 'A' : 'V',
150 : lat_string,
151 : lng_string,
152 : speed_knots,
153 : heading,
154 70 : dstring);
155 70 : if (rmc_res == -1) {
156 0 : free(gga);
157 0 : return;
158 : }
159 : char rmc_end[6];
160 70 : snprintf(rmc_end, sizeof(rmc_end), "*%02X\r\n", (unsigned) _nmea_checksum(rmc));
161 :
162 70 : const uint32_t space_required = strlen(gga) + strlen(gga_end) + strlen(rmc) + strlen(rmc_end);
163 :
164 : // send to all NMEA output ports
165 140 : for (uint8_t i = 0; i < _num_outputs; i++) {
166 70 : if (_uart[i]->txspace() < space_required) {
167 0 : continue;
168 : }
169 :
170 70 : if (gga_res != -1) {
171 70 : _uart[i]->write(gga);
172 70 : _uart[i]->write(gga_end);
173 : }
174 :
175 70 : if (rmc_res != -1) {
176 70 : _uart[i]->write(rmc);
177 70 : _uart[i]->write(rmc_end);
178 : }
179 : }
180 :
181 70 : if (gga_res != -1) {
182 70 : free(gga);
183 : }
184 :
185 70 : if (rmc_res != -1) {
186 70 : free(rmc);
187 : }
188 : }
189 :
190 : #endif // !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE
So my question is regarding these variables loc.lat, loc.lng and loc.alt is where do they get their contents assigned in the firmware please? I am going to admit my C++ skills are quite lacking so I don’t know where to start looking. I assume these are global variables, maybe? Any help would be appreciated
.
[edit] found where loc gets its info in this file, but why is it not showing valid data?
The rest of the code seems to assemble the NMEA sentences as required and sends them to the port.
I see a note in the code that some of this is copied from sitl_gps.cpp. Does the SITL code use the same global variables as the FC code?