@@ -34,6 +34,10 @@ class GeodeticConverter
34
34
35
35
void getReference (double * latitude, double * longitude, double * altitude)
36
36
{
37
+ if ( !isInitialised () )
38
+ {
39
+ throw std::runtime_error (" Illegal method call if not initialized" );
40
+ }
37
41
*latitude = initial_latitude_;
38
42
*longitude = initial_longitude_;
39
43
*altitude = initial_altitude_;
@@ -58,8 +62,15 @@ class GeodeticConverter
58
62
haveReference_ = true ;
59
63
}
60
64
61
- void geodetic2Ecef (const double latitude, const double longitude, const double altitude, double * x,
62
- double * y, double * z)
65
+ // added just to keep the old API
66
+ inline void geodetic2Ecef (const double latitude, const double longitude, const double altitude,
67
+ double * x, double * y, double * z)
68
+ {
69
+ Geodetic2Ecef (latitude, longitude, altitude, x, y, z);
70
+ }
71
+
72
+ static void Geodetic2Ecef (const double latitude, const double longitude, const double altitude,
73
+ double * x, double * y, double * z)
63
74
{
64
75
// Convert geodetic coordinates to ECEF.
65
76
// http://code.google.com/p/pysatel/source/browse/trunk/coord.py?r=22
@@ -71,8 +82,15 @@ class GeodeticConverter
71
82
*z = (kSemimajorAxis / xi * (1 - kFirstEccentricitySquared ) + altitude) * sin (lat_rad);
72
83
}
73
84
74
- void ecef2Geodetic (const double x, const double y, const double z, double * latitude,
75
- double * longitude, double * altitude)
85
+ // added just to keep the old API.
86
+ inline void ecef2Geodetic (const double x, const double y, const double z,
87
+ double * latitude, double * longitude, double * altitude)
88
+ {
89
+ Ecef2Geodetic (x, y, z, latitude, longitude, altitude);
90
+ }
91
+
92
+ static void Ecef2Geodetic (const double x, const double y, const double z,
93
+ double * latitude, double * longitude, double * altitude)
76
94
{
77
95
// Convert ECEF coordinates to geodetic coordinates.
78
96
// J. Zhu, "Conversion of Earth-centered Earth-fixed coordinates
@@ -100,9 +118,13 @@ class GeodeticConverter
100
118
*longitude = rad2Deg (atan2 (y, x));
101
119
}
102
120
103
- void ecef2Ned (const double x, const double y, const double z, double * north, double * east,
104
- double * down)
121
+ void ecef2Ned (const double x, const double y, const double z,
122
+ double * north, double * east, double * down)
105
123
{
124
+ if ( !isInitialised () )
125
+ {
126
+ throw std::runtime_error (" Illegal method call if not initialized" );
127
+ }
106
128
// Converts ECEF coordinate position into local-tangent-plane NED.
107
129
// Coordinates relative to given ECEF coordinate frame.
108
130
@@ -116,9 +138,13 @@ class GeodeticConverter
116
138
*down = -ret (2 );
117
139
}
118
140
119
- void ned2Ecef (const double north, const double east, const double down, double * x, double * y,
120
- double * z)
141
+ void ned2Ecef (const double north, const double east, const double down,
142
+ double * x, double * y, double * z)
121
143
{
144
+ if ( !isInitialised () )
145
+ {
146
+ throw std::runtime_error (" Illegal method call if not initialized" );
147
+ }
122
148
// NED (north/east/down) to ECEF coordinates
123
149
Eigen::Vector3d ned, ret;
124
150
ned (0 ) = north;
@@ -133,27 +159,39 @@ class GeodeticConverter
133
159
void geodetic2Ned (const double latitude, const double longitude, const double altitude,
134
160
double * north, double * east, double * down)
135
161
{
162
+ if ( !isInitialised () )
163
+ {
164
+ throw std::runtime_error (" Illegal method call if not initialized" );
165
+ }
136
166
// Geodetic position to local NED frame
137
167
double x, y, z;
138
- geodetic2Ecef (latitude, longitude, altitude, &x, &y, &z);
168
+ Geodetic2Ecef (latitude, longitude, altitude, &x, &y, &z);
139
169
ecef2Ned (x, y, z, north, east, down);
140
170
}
141
171
142
172
void ned2Geodetic (const double north, const double east, const double down, double * latitude,
143
173
double * longitude, double * altitude)
144
174
{
175
+ if ( !isInitialised () )
176
+ {
177
+ throw std::runtime_error (" Illegal method call if not initialized" );
178
+ }
145
179
// Local NED position to geodetic coordinates
146
180
double x, y, z;
147
181
ned2Ecef (north, east, down, &x, &y, &z);
148
- ecef2Geodetic (x, y, z, latitude, longitude, altitude);
182
+ Ecef2Geodetic (x, y, z, latitude, longitude, altitude);
149
183
}
150
184
151
185
void geodetic2Enu (const double latitude, const double longitude, const double altitude,
152
186
double * east, double * north, double * up)
153
187
{
188
+ if ( !isInitialised () )
189
+ {
190
+ throw std::runtime_error (" Illegal method call if not initialized" );
191
+ }
154
192
// Geodetic position to local ENU frame
155
193
double x, y, z;
156
- geodetic2Ecef (latitude, longitude, altitude, &x, &y, &z);
194
+ Geodetic2Ecef (latitude, longitude, altitude, &x, &y, &z);
157
195
158
196
double aux_north, aux_east, aux_down;
159
197
ecef2Ned (x, y, z, &aux_north, &aux_east, &aux_down);
@@ -163,21 +201,25 @@ class GeodeticConverter
163
201
*up = -aux_down;
164
202
}
165
203
166
- void enu2Geodetic (const double east, const double north, const double up, double * latitude,
167
- double * longitude, double * altitude)
204
+ void enu2Geodetic (const double east, const double north, const double up,
205
+ double * latitude, double * longitude, double * altitude)
168
206
{
207
+ if ( !isInitialised () )
208
+ {
209
+ throw std::runtime_error (" Illegal method call if not initialized" );
210
+ }
169
211
// Local ENU position to geodetic coordinates
170
212
171
213
const double aux_north = north;
172
214
const double aux_east = east;
173
215
const double aux_down = -up;
174
216
double x, y, z;
175
217
ned2Ecef (aux_north, aux_east, aux_down, &x, &y, &z);
176
- ecef2Geodetic (x, y, z, latitude, longitude, altitude);
218
+ Ecef2Geodetic (x, y, z, latitude, longitude, altitude);
177
219
}
178
220
179
221
private:
180
- inline Eigen::Matrix3d nRe (const double lat_radians, const double lon_radians)
222
+ inline static Eigen::Matrix3d nRe (const double lat_radians, const double lon_radians)
181
223
{
182
224
const double sLat = sin (lat_radians);
183
225
const double sLon = sin (lon_radians);
@@ -198,13 +240,13 @@ class GeodeticConverter
198
240
return ret;
199
241
}
200
242
201
- inline
243
+ inline static
202
244
double rad2Deg (const double radians)
203
245
{
204
246
return (radians / M_PI) * 180.0 ;
205
247
}
206
248
207
- inline
249
+ inline static
208
250
double deg2Rad (const double degrees)
209
251
{
210
252
return (degrees / 180.0 ) * M_PI;
@@ -224,6 +266,6 @@ class GeodeticConverter
224
266
bool haveReference_;
225
267
226
268
}; // class GeodeticConverter
227
- }; // namespace geodetic_conv
269
+ } // namespace geodetic_conv
228
270
229
271
#endif // GEODETIC_CONVERTER_H_
0 commit comments