diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index ed527c38824fc..328808e04d9e0 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -92,13 +92,14 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( const double & map_origin_lat, const double & map_origin_lon) { lanelet::ErrorMessages errors{}; - if (lanelet2_map_projector_type == "MGRS") { + if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::MGRS) { lanelet::projection::MGRSProjector projector{}; const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); if (errors.empty()) { return map; } - } else if (lanelet2_map_projector_type == "LocalCartesianUTM") { + } else if ( + lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM) { lanelet::GPSPoint position{map_origin_lat, map_origin_lon}; lanelet::Origin origin{position}; lanelet::projection::UtmProjector projector{origin}; @@ -106,7 +107,7 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map( if (errors.empty()) { return map; } - } else if (lanelet2_map_projector_type == "local") { + } else if (lanelet2_map_projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL) { // Use MGRSProjector as parser lanelet::projection::MGRSProjector projector{}; const lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors); diff --git a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp index f213432b66b50..18306e8d39e25 100644 --- a/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp +++ b/map/map_projection_loader/src/load_info_from_lanelet2_map.cpp @@ -46,15 +46,15 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str tier4_map_msgs::msg::MapProjectorInfo msg; if (is_local) { - msg.projector_type = "local"; + msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::LOCAL; } else { - msg.projector_type = "MGRS"; + msg.projector_type = tier4_map_msgs::msg::MapProjectorInfo::MGRS; msg.mgrs_grid = projector.getProjectedMGRSGrid(); } // We assume that the vertical datum of the map is WGS84 when using lanelet2 map. // However, do note that this is not always true, and may cause problems in the future. // Thus, please consider using the map_projector_info.yaml instead of this deprecated function. - msg.vertical_datum = "WGS84"; + msg.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84; return msg; } diff --git a/map/map_projection_loader/src/map_projection_loader.cpp b/map/map_projection_loader/src/map_projection_loader.cpp index ec38f0ff3642e..79083b755fb26 100644 --- a/map/map_projection_loader/src/map_projection_loader.cpp +++ b/map/map_projection_loader/src/map_projection_loader.cpp @@ -28,14 +28,14 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & fi tier4_map_msgs::msg::MapProjectorInfo msg; msg.projector_type = data["projector_type"].as(); - if (msg.projector_type == "MGRS") { + if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::MGRS) { msg.vertical_datum = data["vertical_datum"].as(); msg.mgrs_grid = data["mgrs_grid"].as(); - } else if (msg.projector_type == "LocalCartesianUTM") { + } else if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM) { msg.vertical_datum = data["vertical_datum"].as(); msg.map_origin.latitude = data["map_origin"]["latitude"].as(); msg.map_origin.longitude = data["map_origin"]["longitude"].as(); - } else if (msg.projector_type == "local") { + } else if (msg.projector_type == tier4_map_msgs::msg::MapProjectorInfo::LOCAL) { ; // do nothing } else { throw std::runtime_error( diff --git a/system/default_ad_api/src/vehicle.cpp b/system/default_ad_api/src/vehicle.cpp index 43efdb2adfaf8..fb434adbb0e40 100644 --- a/system/default_ad_api/src/vehicle.cpp +++ b/system/default_ad_api/src/vehicle.cpp @@ -146,7 +146,7 @@ void VehicleNode::publish_kinematics() vehicle_kinematics.twist.header = kinematic_state_msgs_->header; vehicle_kinematics.twist.header.frame_id = kinematic_state_msgs_->child_frame_id; vehicle_kinematics.twist.twist = kinematic_state_msgs_->twist; - if (map_projector_info_->projector_type == "MGRS") { + if (map_projector_info_->projector_type == MapProjectorInfo::MGRS) { lanelet::GPSPoint projected_gps_point = lanelet::projection::MGRSProjector::reverse( toBasicPoint3dPt(kinematic_state_msgs_->pose.pose.position), map_projector_info_->mgrs_grid); vehicle_kinematics.geographic_pose.header = kinematic_state_msgs_->header; @@ -154,7 +154,7 @@ void VehicleNode::publish_kinematics() vehicle_kinematics.geographic_pose.position.latitude = projected_gps_point.lat; vehicle_kinematics.geographic_pose.position.longitude = projected_gps_point.lon; vehicle_kinematics.geographic_pose.position.altitude = projected_gps_point.ele; - } else if (map_projector_info_->projector_type == "LocalCartesianUTM") { + } else if (map_projector_info_->projector_type == MapProjectorInfo::LOCAL_CARTESIAN_UTM) { lanelet::GPSPoint position{ map_projector_info_->map_origin.latitude, map_projector_info_->map_origin.longitude}; lanelet::Origin origin{position};