Skip to content

Commit 66c6e15

Browse files
feat: use constant string for map_projector_info (autowarefoundation#4789)
* feat: use constant string for map_projector_info Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * update Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent c75a8eb commit 66c6e15

File tree

4 files changed

+12
-11
lines changed

4 files changed

+12
-11
lines changed

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -92,21 +92,22 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
9292
const double & map_origin_lat, const double & map_origin_lon)
9393
{
9494
lanelet::ErrorMessages errors{};
95-
if (lanelet2_map_projector_type == "MGRS") {
95+
if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::MGRS) {
9696
lanelet::projection::MGRSProjector projector{};
9797
const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors);
9898
if (errors.empty()) {
9999
return map;
100100
}
101-
} else if (lanelet2_map_projector_type == "LocalCartesianUTM") {
101+
} else if (
102+
lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM) {
102103
lanelet::GPSPoint position{map_origin_lat, map_origin_lon};
103104
lanelet::Origin origin{position};
104105
lanelet::projection::UtmProjector projector{origin};
105106
const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors);
106107
if (errors.empty()) {
107108
return map;
108109
}
109-
} else if (lanelet2_map_projector_type == "local") {
110+
} else if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL) {
110111
// Use MGRSProjector as parser
111112
lanelet::projection::MGRSProjector projector{};
112113
const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors);

map/map_projection_loader/src/load_info_from_lanelet2_map.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -46,15 +46,15 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str
4646

4747
tier4_map_msgs::msg::MapProjectorInfo msg;
4848
if (is_local) {
49-
msg.projector_type = "local";
49+
msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL;
5050
} else {
51-
msg.projector_type = "MGRS";
51+
msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS;
5252
msg.mgrs_grid = projector.getProjectedMGRSGrid();
5353
}
5454

5555
// We assume that the vertical datum of the map is WGS84 when using lanelet2 map.
5656
// However, do note that this is not always true, and may cause problems in the future.
5757
// 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;
5959
return msg;
6060
}

map/map_projection_loader/src/map_projection_loader.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -28,14 +28,14 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi
2828

2929
tier4_map_msgs::msg::MapProjectorInfo msg;
3030
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) {
3232
msg.vertical_datum = data["vertical_datum"].as<std::string>();
3333
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) {
3535
msg.vertical_datum = data["vertical_datum"].as<std::string>();
3636
msg.map_origin.latitude = data["map_origin"]["latitude"].as<double>();
3737
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) {
3939
; // do nothing
4040
} else {
4141
throw std::runtime_error(

system/default_ad_api/src/vehicle.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -146,15 +146,15 @@ void VehicleNode::publish_kinematics()
146146
vehicle_kinematics.twist.header = kinematic_state_msgs_->header;
147147
vehicle_kinematics.twist.header.frame_id = kinematic_state_msgs_->child_frame_id;
148148
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) {
150150
lanelet::GPSPoint projected_gps_point = lanelet::projection::MGRSProjector::reverse(
151151
toBasicPoint3dPt(kinematic_state_msgs_->pose.pose.position), map_projector_info_->mgrs_grid);
152152
vehicle_kinematics.geographic_pose.header = kinematic_state_msgs_->header;
153153
vehicle_kinematics.geographic_pose.header.frame_id = "global";
154154
vehicle_kinematics.geographic_pose.position.latitude = projected_gps_point.lat;
155155
vehicle_kinematics.geographic_pose.position.longitude = projected_gps_point.lon;
156156
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) {
158158
lanelet::GPSPoint position{
159159
map_projector_info_->map_origin.latitude, map_projector_info_->map_origin.longitude};
160160
lanelet::Origin origin{position};

0 commit comments

Comments
 (0)