Skip to content

feat(projection): add_scale_factor #54

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
Apr 4, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,8 @@ inline namespace format_v2
class TransverseMercatorProjector : public Projector
{
public:
explicit TransverseMercatorProjector(Origin origin = Origin({0.0, 0.0}));
explicit TransverseMercatorProjector(
Origin origin = Origin({0.0, 0.0}), const double scale_factor = 0.9996);

/**
* [TransverseMercatorProjector::forward projects gps lat/lon to Transverse Mercator coordinate]
Expand All @@ -55,6 +56,11 @@ class TransverseMercatorProjector : public Projector
double origin_x_;
double origin_y_;
double central_meridian_;

/**
* scale factor of the map
*/
double scale_factor_;
};
} // namespace format_v2

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,21 +24,22 @@

namespace lanelet::projection
{
TransverseMercatorProjector::TransverseMercatorProjector(Origin origin) : Projector(origin)
TransverseMercatorProjector::TransverseMercatorProjector(Origin origin, const double scale_factor)
: Projector(origin)
{
central_meridian_ = origin.position.lon;

scale_factor_ = scale_factor;
// Calculate origin in Transverse Mercator coordinate
const GeographicLib::TransverseMercatorExact & proj =
GeographicLib::TransverseMercatorExact::UTM();
const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact(
GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f(), scale_factor_);
proj.Forward(central_meridian_, origin.position.lat, origin.position.lon, origin_x_, origin_y_);
}

BasicPoint3d TransverseMercatorProjector::forward(const GPSPoint & gps) const
{
BasicPoint3d tm_point{0., 0., gps.ele};
const GeographicLib::TransverseMercatorExact & proj =
GeographicLib::TransverseMercatorExact::UTM();
const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact(
GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f(), scale_factor_);
proj.Forward(central_meridian_, gps.lat, gps.lon, tm_point.x(), tm_point.y());

// x is already aligned with origin as it is projected in transverse mercator
Expand All @@ -50,8 +51,8 @@ BasicPoint3d TransverseMercatorProjector::forward(const GPSPoint & gps) const
GPSPoint TransverseMercatorProjector::reverse(const BasicPoint3d & local_point) const
{
GPSPoint gps{0.0, 0.0, local_point.z()};
const GeographicLib::TransverseMercatorExact & proj =
GeographicLib::TransverseMercatorExact::UTM();
const GeographicLib::TransverseMercatorExact & proj = GeographicLib::TransverseMercatorExact(
GeographicLib::Constants::WGS84_a(), GeographicLib::Constants::WGS84_f(), scale_factor_);

BasicPoint3d local_point_copy = local_point;
local_point_copy.y() = local_point.y() + origin_y_;
Expand Down
Loading