QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
ULogParser.cc
Go to the documentation of this file.
1#include "ULogParser.h"
2#include "ULogUtility.h"
4
5#include <cmath>
6
7QGC_LOGGING_CATEGORY(ULogParserLog, "AnalyzeView.ULogParser")
8
9namespace ULogParser {
10
11GeoTagData parseGeoTagData(const ulog_cpp::TypedDataView &sample)
12{
13 GeoTagData feedback;
14
15 // Required fields (timestamp in microseconds, convert to seconds)
16 feedback.timestamp = static_cast<qint64>(sample.at("timestamp").as<uint64_t>() / 1000000);
17 feedback.imageSequence = sample.at("seq").as<uint32_t>();
18
19 // Coordinate fields
20 double longitude = sample.at("lon").as<double>();
21 longitude = fmod(180.0 + longitude, 360.0) - 180.0;
22 feedback.coordinate = QGeoCoordinate(
23 sample.at("lat").as<double>(),
24 longitude,
25 sample.at("alt").as<float>()
26 );
27
28 // Optional fields with hasField() checks
29 if (sample.hasField("timestamp_utc")) {
30 feedback.timestampUTC = static_cast<qint64>(sample.at("timestamp_utc").as<uint64_t>() / 1000000);
31 }
32
33 if (sample.hasField("ground_distance")) {
34 feedback.groundDistance = sample.at("ground_distance").as<float>();
35 }
36
37 if (sample.hasField("q")) {
38 feedback.attitude = QQuaternion(
39 sample.at("q")[0].as<float>(),
40 sample.at("q")[1].as<float>(),
41 sample.at("q")[2].as<float>(),
42 sample.at("q")[3].as<float>()
43 );
44 }
45
46 if (sample.hasField("result")) {
47 feedback.captureResult = static_cast<GeoTagData::CaptureResult>(sample.at("result").as<int8_t>());
48 } else {
49 // For backwards compatibility with older ULog files that don't have the result field,
50 // assume success if we got valid coordinate data
52 }
53
54 return feedback;
55}
56
57bool getTagsFromLog(const char *data, qint64 size, QList<GeoTagData> &cameraFeedback, QString &errorMessage)
58{
59 cameraFeedback.clear();
60
61 const bool success = ULogUtility::iterateMessages(data, size, "camera_capture",
62 [&](const ulog_cpp::TypedDataView &sample) {
63 cameraFeedback.append(parseGeoTagData(sample));
64 return true;
65 }, errorMessage);
66
67 if (!success) {
68 return false;
69 }
70
71 if (cameraFeedback.isEmpty()) {
72 errorMessage = QStringLiteral("Could not detect camera_capture packets in ULog");
73 return false;
74 }
75
76 return true;
77}
78
79} // namespace ULogParser
#define QGC_LOGGING_CATEGORY(name, categoryStr)
GeoTagData parseGeoTagData(const ulog_cpp::TypedDataView &sample)
Definition ULogParser.cc:11
bool iterateMessages(const char *data, qint64 size, const std::string &messageName, const MessageCallback &callback, QString &errorMessage)
float groundDistance
Definition GeoTagData.h:18
uint32_t imageSequence
Definition GeoTagData.h:16
QGeoCoordinate coordinate
Definition GeoTagData.h:17
qint64 timestampUTC
Seconds since epoch (UTC)
Definition GeoTagData.h:15
QQuaternion attitude
Definition GeoTagData.h:19
qint64 timestamp
Seconds since epoch.
Definition GeoTagData.h:14
CaptureResult captureResult
Definition GeoTagData.h:20