Skip to content

Commit 08ca139

Browse files
committed
Added generic gps point utility class
1 parent 77c713d commit 08ca139

File tree

1 file changed

+223
-0
lines changed

1 file changed

+223
-0
lines changed

math/gps_util.h

+223
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,223 @@
1+
#ifndef GPS_UTIL_H_
2+
#define GPS_UTIL_H_
3+
4+
#include <math.h>
5+
6+
#include <cmath>
7+
#include <string>
8+
#include <tuple>
9+
10+
#include "eigen3/Eigen/Dense"
11+
#include "shared/math/math_util.h"
12+
#include "shared/util/helpers.h"
13+
14+
using Eigen::Rotation2Dd;
15+
using Eigen::Vector2d;
16+
using math_util::DegToRad;
17+
using std::string;
18+
19+
namespace gps_util {
20+
21+
struct GPSPoint {
22+
// Convenience data structure for GPS points.
23+
GPSPoint() : time(0), lat(0), lon(0) {}
24+
GPSPoint(double time, double lat, double lon)
25+
: time(time), lat(lat), lon(lon) {}
26+
GPSPoint(double time, double lat, double lon, double heading)
27+
: time(time), lat(lat), lon(lon), heading(heading) {}
28+
GPSPoint(double lat, double lon) : time(0), lat(lat), lon(lon) {}
29+
30+
bool operator==(const GPSPoint& other) const {
31+
return lat == other.lat && lon == other.lon;
32+
}
33+
34+
bool operator!=(const GPSPoint& other) const { return !(*this == other); }
35+
36+
double time;
37+
double lat;
38+
double lon;
39+
double heading; // True North
40+
};
41+
42+
struct GPSTranslator {
43+
string GetMapFileFromName(const string& maps_dir, const string& map) {
44+
return maps_dir + "/" + map + "/" + map + ".gpsmap.txt";
45+
}
46+
47+
bool Load(const string& maps_dir, const string& map) {
48+
const string file = GetMapFileFromName(maps_dir, map);
49+
ScopedFile fid(file, "r", true);
50+
if (fid() == nullptr) return false;
51+
if (fscanf(fid(), "%lf, %lf, %lf", &gps_origin_latitude,
52+
&gps_origin_longitude, &map_orientation) != 3) {
53+
return false;
54+
}
55+
printf("Map origin: %12.8lf, %12.8lf\n", gps_origin_latitude,
56+
gps_origin_longitude);
57+
return true;
58+
}
59+
60+
Vector2d GPSToMetric(const double latitude, const double longitude) {
61+
const double theta = DegToRad(latitude);
62+
const double c = std::cos(theta);
63+
const double s = std::sin(theta);
64+
const double r =
65+
sqrt(Sq(wgs_84_a * wgs_84_b) / (Sq(c * wgs_84_b) + Sq(s * wgs_84_a)));
66+
const double dlat = DegToRad(latitude - gps_origin_latitude);
67+
const double dlong = DegToRad(longitude - gps_origin_longitude);
68+
const double r1 = r * c;
69+
const double x = r1 * dlong;
70+
const double y = r * dlat;
71+
return Rotation2Dd(map_orientation) * Vector2d(x, y);
72+
}
73+
74+
void MetricToGPS(const Vector2d& loc, double* longitude, double* latitude) {
75+
const double theta = DegToRad(gps_origin_latitude);
76+
const double c = std::cos(theta);
77+
const double s = std::sin(theta);
78+
const double r =
79+
sqrt(Sq(wgs_84_a * wgs_84_b) / (Sq(c * wgs_84_b) + Sq(s * wgs_84_a)));
80+
const double r1 = r * c;
81+
const double dlat = loc.y() / r;
82+
const double dlong = loc.x() / r1;
83+
*longitude = gps_origin_longitude + dlong;
84+
*latitude = gps_origin_latitude + dlat;
85+
}
86+
87+
double gps_origin_longitude;
88+
double gps_origin_latitude;
89+
double map_orientation;
90+
91+
// Earth geoid parameters from WGS 84 system
92+
// https://en.wikipedia.org/wiki/World_Geodetic_System#A_new_World_Geodetic_System:_WGS_84
93+
// a = Semimajor (Equatorial) axis
94+
static constexpr double wgs_84_a = 6378137.0;
95+
// b = Semiminor (Polar) axis
96+
static constexpr double wgs_84_b = 6356752.314245;
97+
};
98+
99+
inline std::tuple<double, double, int> gpsToUTM(double lat, double lon) {
100+
// Constants for UTM conversion
101+
constexpr double a = 6378137.0; // WGS-84 major axis
102+
constexpr double f = 1 / 298.257223563; // WGS-84 flattening
103+
constexpr double k0 = 0.9996; // UTM scale factor
104+
constexpr double e = sqrt(f * (2 - f)); // Eccentricity
105+
constexpr double e2 = e * e;
106+
107+
// UTM Zone
108+
int zone = static_cast<int>((lon + 180) / 6) + 1;
109+
110+
// Convert latitude and longitude to radians
111+
double lat_rad = lat * M_PI / 180.0;
112+
double lon_rad = lon * M_PI / 180.0;
113+
114+
// Central meridian of the UTM zone
115+
double lon_origin = (zone - 1) * 6 - 180 + 3;
116+
double lon_origin_rad = lon_origin * M_PI / 180.0;
117+
118+
// Calculations for UTM coordinates
119+
double N = a / sqrt(1 - e2 * sin(lat_rad) * sin(lat_rad));
120+
double T = tan(lat_rad) * tan(lat_rad);
121+
double C = e2 / (1 - e2) * cos(lat_rad) * cos(lat_rad);
122+
double A = cos(lat_rad) * (lon_rad - lon_origin_rad);
123+
124+
double M =
125+
a * ((1 - e2 / 4 - 3 * e2 * e2 / 64 - 5 * e2 * e2 * e2 / 256) * lat_rad -
126+
(3 * e2 / 8 + 3 * e2 * e2 / 32 + 45 * e2 * e2 * e2 / 1024) *
127+
sin(2 * lat_rad) +
128+
(15 * e2 * e2 / 256 + 45 * e2 * e2 * e2 / 1024) * sin(4 * lat_rad) -
129+
(35 * e2 * e2 * e2 / 3072) * sin(6 * lat_rad));
130+
131+
double easting =
132+
k0 * N *
133+
(A + (1 - T + C) * A * A * A / 6 +
134+
(5 - 18 * T + T * T + 72 * C - 58 * e2) * A * A * A * A * A / 120) +
135+
500000.0;
136+
137+
double northing =
138+
k0 *
139+
(M + N * tan(lat_rad) *
140+
(A * A / 2 + (5 - T + 9 * C + 4 * C * C) * A * A * A * A / 24 +
141+
(61 - 58 * T + T * T + 600 * C - 330 * e2) * A * A * A * A * A *
142+
A / 720));
143+
144+
// Correct for southern hemisphere
145+
if (lat < 0) {
146+
northing += 10000000.0;
147+
}
148+
149+
return std::make_tuple(easting, northing, zone);
150+
}
151+
152+
inline double gpsDistance(double lat0, double lon0, double lat1, double lon1) {
153+
// Convert latitude and longitude to radians
154+
double lat0_rad = lat0 * M_PI / 180.0;
155+
double lon0_rad = lon0 * M_PI / 180.0;
156+
double lat1_rad = lat1 * M_PI / 180.0;
157+
double lon1_rad = lon1 * M_PI / 180.0;
158+
159+
// Haversine formula for distance between two GPS coordinates
160+
double dlat = lat1_rad - lat0_rad;
161+
double dlon = lon1_rad - lon0_rad;
162+
double a = pow(sin(dlat / 2), 2) +
163+
cos(lat0_rad) * cos(lat1_rad) * pow(sin(dlon / 2), 2);
164+
double c = 2 * atan2(sqrt(a), sqrt(1 - a));
165+
return 6371000 * c; // Radius of Earth in meters
166+
}
167+
168+
inline std::tuple<double, double> gpsToGlobalCoord(double lat0, double lon0,
169+
double lat1, double lon1) {
170+
// Convert latitude and longitude to utm coordinates
171+
const auto& [e0, n0, zone0] = gpsToUTM(lat0, lon0);
172+
const auto& [e1, n1, zone1] = gpsToUTM(lat1, lon1);
173+
return {e1 - e0, n1 - n0};
174+
}
175+
176+
inline Eigen::Affine2f gpsToLocal(double current_lat, double current_lon,
177+
double current_heading, double goal_lat,
178+
double goal_lon, double goal_heading) {
179+
// Step 1: Convert current and goal GPS coordinates to UTM
180+
const auto& [curr_easting, curr_northing, curr_zone] =
181+
gpsToUTM(current_lat, current_lon);
182+
const auto& [goal_easting, goal_northing, goal_zone] =
183+
gpsToUTM(goal_lat, goal_lon);
184+
// Ensure that both coordinates are in the same UTM zone
185+
if (goal_zone != curr_zone) {
186+
throw std::runtime_error("GPS points are in different UTM zones.");
187+
}
188+
189+
// Step 2: Calculate the translation vector from the current position to the
190+
// goal in UTM
191+
double dx = goal_easting - curr_easting;
192+
double dy = goal_northing - curr_northing;
193+
194+
// Step 3: Convert the current heading to radians and adjust for x-axis
195+
// reference Since 0 degrees points along the y-axis and rotates
196+
// counter-clockwise, convert to radians with 0 degrees aligned along the
197+
// x-axis
198+
double current_heading_rad = (90.0 - current_heading) * M_PI / 180.0;
199+
200+
// Step 4: Rotate the translation vector to the robot's local frame
201+
double local_x =
202+
dx * cos(-current_heading_rad) - dy * sin(-current_heading_rad);
203+
double local_y =
204+
dx * sin(-current_heading_rad) + dy * cos(-current_heading_rad);
205+
206+
// Step 5: Convert the goal heading to the local frame
207+
double goal_heading_rad = (90.0 - goal_heading) * M_PI / 180.0;
208+
double local_heading = goal_heading_rad - current_heading_rad;
209+
210+
// Normalize local heading to the range [-pi, pi]
211+
while (local_heading > M_PI) local_heading -= 2 * M_PI;
212+
while (local_heading < -M_PI) local_heading += 2 * M_PI;
213+
214+
// Step 6: Create the affine transformation for the local pose of the goal
215+
Eigen::Affine2f transform = Eigen::Translation2f(local_x, local_y) *
216+
Eigen::Rotation2Df(local_heading);
217+
218+
return transform;
219+
}
220+
221+
} // namespace gps_util
222+
223+
#endif

0 commit comments

Comments
 (0)