Skip to content

Commit 3a96889

Browse files
feat(projection): add_scale_factor (#54)
* add_scale_factor Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent b5acecf commit 3a96889

File tree

2 files changed

+16
-9
lines changed

2 files changed

+16
-9
lines changed

autoware_lanelet2_extension/include/autoware_lanelet2_extension/projection/transverse_mercator_projector.hpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,8 @@ inline namespace format_v2
3333
class TransverseMercatorProjector : public Projector
3434
{
3535
public:
36-
explicit TransverseMercatorProjector(Origin origin = Origin({0.0, 0.0}));
36+
explicit TransverseMercatorProjector(
37+
Origin origin = Origin({0.0, 0.0}), const double scale_factor = 0.9996);
3738

3839
/**
3940
* [TransverseMercatorProjector::forward projects gps lat/lon to Transverse Mercator coordinate]
@@ -55,6 +56,11 @@ class TransverseMercatorProjector : public Projector
5556
double origin_x_;
5657
double origin_y_;
5758
double central_meridian_;
59+
60+
/**
61+
* scale factor of the map
62+
*/
63+
double scale_factor_;
5864
};
5965
} // namespace format_v2
6066

autoware_lanelet2_extension/lib/transverse_mercator_projector.cpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -24,21 +24,22 @@
2424

2525
namespace lanelet::projection
2626
{
27-
TransverseMercatorProjector::TransverseMercatorProjector(Origin origin) : Projector(origin)
27+
TransverseMercatorProjector::TransverseMercatorProjector(Origin origin, const double scale_factor)
28+
: Projector(origin)
2829
{
2930
central_meridian_ = origin.position.lon;
30-
31+
scale_factor_ = scale_factor;
3132
// 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_);
3435
proj.Forward(central_meridian_, origin.position.lat, origin.position.lon, origin_x_, origin_y_);
3536
}
3637

3738
BasicPoint3d TransverseMercatorProjector::forward(const GPSPoint & gps) const
3839
{
3940
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_);
4243
proj.Forward(central_meridian_, gps.lat, gps.lon, tm_point.x(), tm_point.y());
4344

4445
// x is already aligned with origin as it is projected in transverse mercator
@@ -50,8 +51,8 @@ BasicPoint3d TransverseMercatorProjector::forward(const GPSPoint & gps) const
5051
GPSPoint TransverseMercatorProjector::reverse(const BasicPoint3d & local_point) const
5152
{
5253
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_);
5556

5657
BasicPoint3d local_point_copy = local_point;
5758
local_point_copy.y() = local_point.y() + origin_y_;

0 commit comments

Comments
 (0)