24
24
25
25
namespace lanelet ::projection
26
26
{
27
- TransverseMercatorProjector::TransverseMercatorProjector (Origin origin) : Projector(origin)
27
+ TransverseMercatorProjector::TransverseMercatorProjector (Origin origin, const double scale_factor)
28
+ : Projector(origin)
28
29
{
29
30
central_meridian_ = origin.position .lon ;
30
-
31
+ scale_factor_ = scale_factor;
31
32
// Calculate origin in Transverse Mercator coordinate
32
- const GeographicLib::TransverseMercatorExact & proj =
33
- GeographicLib::TransverseMercatorExact::UTM ( );
33
+ const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact (
34
+ GeographicLib::Constants::WGS84_a (), GeographicLib::Constants::WGS84_f (), scale_factor_ );
34
35
proj.Forward (central_meridian_, origin.position .lat , origin.position .lon , origin_x_, origin_y_);
35
36
}
36
37
37
38
BasicPoint3d TransverseMercatorProjector::forward (const GPSPoint & gps) const
38
39
{
39
40
BasicPoint3d tm_point{0 ., 0 ., gps.ele };
40
- const GeographicLib::TransverseMercatorExact & proj =
41
- GeographicLib::TransverseMercatorExact::UTM ( );
41
+ const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact (
42
+ GeographicLib::Constants::WGS84_a (), GeographicLib::Constants::WGS84_f (), scale_factor_ );
42
43
proj.Forward (central_meridian_, gps.lat , gps.lon , tm_point.x (), tm_point.y ());
43
44
44
45
// x is already aligned with origin as it is projected in transverse mercator
@@ -50,8 +51,8 @@ BasicPoint3d TransverseMercatorProjector::forward(const GPSPoint & gps) const
50
51
GPSPoint TransverseMercatorProjector::reverse (const BasicPoint3d & local_point) const
51
52
{
52
53
GPSPoint gps{0.0 , 0.0 , local_point.z ()};
53
- const GeographicLib::TransverseMercatorExact & proj =
54
- GeographicLib::TransverseMercatorExact::UTM ( );
54
+ const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact (
55
+ GeographicLib::Constants::WGS84_a (), GeographicLib::Constants::WGS84_f (), scale_factor_ );
55
56
56
57
BasicPoint3d local_point_copy = local_point;
57
58
local_point_copy.y () = local_point.y () + origin_y_;
0 commit comments