File tree 4 files changed +12
-11
lines changed
map_loader/src/lanelet2_map_loader
map_projection_loader/src
system/default_ad_api/src
4 files changed +12
-11
lines changed Original file line number Diff line number Diff line change @@ -92,21 +92,22 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
92
92
const double & map_origin_lat, const double & map_origin_lon)
93
93
{
94
94
lanelet::ErrorMessages errors{};
95
- if (lanelet2_map_projector_type == " MGRS" ) {
95
+ if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo:: MGRS) {
96
96
lanelet::projection::MGRSProjector projector{};
97
97
const lanelet::LaneletMapPtr map = lanelet::load (lanelet2_filename, projector, &errors);
98
98
if (errors.empty ()) {
99
99
return map;
100
100
}
101
- } else if (lanelet2_map_projector_type == " LocalCartesianUTM" ) {
101
+ } else if (
102
+ lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM) {
102
103
lanelet::GPSPoint position{map_origin_lat, map_origin_lon};
103
104
lanelet::Origin origin{position};
104
105
lanelet::projection::UtmProjector projector{origin};
105
106
const lanelet::LaneletMapPtr map = lanelet::load (lanelet2_filename, projector, &errors);
106
107
if (errors.empty ()) {
107
108
return map;
108
109
}
109
- } else if (lanelet2_map_projector_type == " local " ) {
110
+ } else if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL ) {
110
111
// Use MGRSProjector as parser
111
112
lanelet::projection::MGRSProjector projector{};
112
113
const lanelet::LaneletMapPtr map = lanelet::load (lanelet2_filename, projector, &errors);
Original file line number Diff line number Diff line change @@ -46,15 +46,15 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str
46
46
47
47
tier4_map_msgs::msg::MapProjectorInfo msg;
48
48
if (is_local) {
49
- msg.projector_type = " local " ;
49
+ msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL ;
50
50
} else {
51
- msg.projector_type = " MGRS" ;
51
+ msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo:: MGRS;
52
52
msg.mgrs_grid = projector.getProjectedMGRSGrid ();
53
53
}
54
54
55
55
// We assume that the vertical datum of the map is WGS84 when using lanelet2 map.
56
56
// However, do note that this is not always true, and may cause problems in the future.
57
57
// Thus, please consider using the map_projector_info.yaml instead of this deprecated function.
58
- msg.vertical_datum = " WGS84" ;
58
+ msg.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo:: WGS84;
59
59
return msg;
60
60
}
Original file line number Diff line number Diff line change @@ -28,14 +28,14 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi
28
28
29
29
tier4_map_msgs::msg::MapProjectorInfo msg;
30
30
msg.projector_type = data[" projector_type" ].as <std::string>();
31
- if (msg.projector_type == " MGRS" ) {
31
+ if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo:: MGRS) {
32
32
msg.vertical_datum = data[" vertical_datum" ].as <std::string>();
33
33
msg.mgrs_grid = data[" mgrs_grid" ].as <std::string>();
34
- } else if (msg.projector_type == " LocalCartesianUTM " ) {
34
+ } else if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM ) {
35
35
msg.vertical_datum = data[" vertical_datum" ].as <std::string>();
36
36
msg.map_origin .latitude = data[" map_origin" ][" latitude" ].as <double >();
37
37
msg.map_origin .longitude = data[" map_origin" ][" longitude" ].as <double >();
38
- } else if (msg.projector_type == " local " ) {
38
+ } else if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL ) {
39
39
; // do nothing
40
40
} else {
41
41
throw std::runtime_error (
Original file line number Diff line number Diff line change @@ -146,15 +146,15 @@ void VehicleNode::publish_kinematics()
146
146
vehicle_kinematics.twist .header = kinematic_state_msgs_->header ;
147
147
vehicle_kinematics.twist .header .frame_id = kinematic_state_msgs_->child_frame_id ;
148
148
vehicle_kinematics.twist .twist = kinematic_state_msgs_->twist ;
149
- if (map_projector_info_->projector_type == " MGRS" ) {
149
+ if (map_projector_info_->projector_type == MapProjectorInfo:: MGRS) {
150
150
lanelet::GPSPoint projected_gps_point = lanelet::projection::MGRSProjector::reverse (
151
151
toBasicPoint3dPt (kinematic_state_msgs_->pose .pose .position ), map_projector_info_->mgrs_grid );
152
152
vehicle_kinematics.geographic_pose .header = kinematic_state_msgs_->header ;
153
153
vehicle_kinematics.geographic_pose .header .frame_id = " global" ;
154
154
vehicle_kinematics.geographic_pose .position .latitude = projected_gps_point.lat ;
155
155
vehicle_kinematics.geographic_pose .position .longitude = projected_gps_point.lon ;
156
156
vehicle_kinematics.geographic_pose .position .altitude = projected_gps_point.ele ;
157
- } else if (map_projector_info_->projector_type == " LocalCartesianUTM " ) {
157
+ } else if (map_projector_info_->projector_type == MapProjectorInfo::LOCAL_CARTESIAN_UTM ) {
158
158
lanelet::GPSPoint position{
159
159
map_projector_info_->map_origin .latitude , map_projector_info_->map_origin .longitude };
160
160
lanelet::Origin origin{position};
You can’t perform that action at this time.
0 commit comments