From 4da1fb3b703800b9ef8fdbd777be83c96c247779 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Antkiewicz?= Date: Tue, 5 Dec 2023 12:26:55 -0500 Subject: [PATCH] initialize origin to a non-default one to avoid throwing the exception by IOHandler::handleDefaultProjector --- lanelet2_projection/include/lanelet2_projection/Geocentric.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/lanelet2_projection/include/lanelet2_projection/Geocentric.h b/lanelet2_projection/include/lanelet2_projection/Geocentric.h index 33808e00..93737efb 100644 --- a/lanelet2_projection/include/lanelet2_projection/Geocentric.h +++ b/lanelet2_projection/include/lanelet2_projection/Geocentric.h @@ -6,6 +6,9 @@ namespace projection { class GeocentricProjector : public Projector { public: + // initialize the origin so that it's not the default one which causes + // IOHandler::handleDefaultProjector to throw an exception + GeocentricProjector() : Projector{Origin({90.0, 0.0, -6356752.3})} {} BasicPoint3d forward(const GPSPoint& gps) const override; GPSPoint reverse(const BasicPoint3d& enu) const override; };