File tree 3 files changed +25
-1
lines changed
common/autoware_geography_utils/src
map/autoware_map_projection_loader
3 files changed +25
-1
lines changed Original file line number Diff line number Diff line change 17
17
#include < autoware_lanelet2_extension/projection/mgrs_projector.hpp>
18
18
#include < autoware_lanelet2_extension/projection/transverse_mercator_projector.hpp>
19
19
20
+ #include < lanelet2_projection/LocalCartesian.h>
20
21
#include < lanelet2_projection/UTM.h>
21
22
22
23
namespace autoware ::geography_utils
@@ -44,6 +45,13 @@ std::unique_ptr<lanelet::Projector> get_lanelet2_projector(const MapProjectorInf
44
45
lanelet::Origin origin{position};
45
46
lanelet::projection::TransverseMercatorProjector projector{origin};
46
47
return std::make_unique<lanelet::projection::TransverseMercatorProjector>(projector);
48
+ } else if (projector_info.projector_type == MapProjectorInfo::LOCAL_CARTESIAN) {
49
+ lanelet::GPSPoint position{
50
+ projector_info.map_origin .latitude , projector_info.map_origin .longitude ,
51
+ projector_info.map_origin .altitude };
52
+ lanelet::Origin origin{position};
53
+ lanelet::projection::LocalCartesianProjector projector{origin};
54
+ return std::make_unique<lanelet::projection::LocalCartesianProjector>(projector);
47
55
}
48
56
const std::string error_msg =
49
57
" Invalid map projector type: " + projector_info.projector_type +
Original file line number Diff line number Diff line change @@ -70,6 +70,20 @@ map_origin:
70
70
altitude : 0.0 # [m]
71
71
` ` `
72
72
73
+ ### Using LocalCartesian
74
+
75
+ If you want to use local cartesian WGS84, please specify the map origin as well.
76
+
77
+ ` ` ` yaml
78
+ # map_projector_info.yaml
79
+ projector_type : LocalCartesian
80
+ vertical_datum : WGS84
81
+ map_origin :
82
+ latitude : 35.6762 # [deg]
83
+ longitude : 139.6503 # [deg]
84
+ altitude : 0.0 # [m]
85
+ ` ` `
86
+
73
87
### Using TransverseMercator
74
88
75
89
If you want to use Transverse Mercator projection, please specify the map origin as well.
Original file line number Diff line number Diff line change @@ -37,6 +37,7 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi
37
37
38
38
} else if (
39
39
msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM ||
40
+ msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN ||
40
41
msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::TRANSVERSE_MERCATOR) {
41
42
msg.vertical_datum = data[" vertical_datum" ].as <std::string>();
42
43
msg.map_origin .latitude = data[" map_origin" ][" latitude" ].as <double >();
@@ -48,7 +49,8 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi
48
49
49
50
} else {
50
51
throw std::runtime_error (
51
- " Invalid map projector type. Currently supported types: MGRS, LocalCartesianUTM, "
52
+ " Invalid map projector type. Currently supported types: MGRS, LocalCartesian, "
53
+ " LocalCartesianUTM, "
52
54
" TransverseMercator, and local" );
53
55
}
54
56
return msg;
You can’t perform that action at this time.
0 commit comments