diff --git a/build_depends_humble.repos b/build_depends_humble.repos index 772b9e1050138..0f35bd3d0e357 100644 --- a/build_depends_humble.repos +++ b/build_depends_humble.repos @@ -19,7 +19,7 @@ repositories: core/autoware_msgs: type: git url: https://github.com/autowarefoundation/autoware_msgs.git - version: 1.3.0 + version: 1.4.0 core/autoware_adapi_msgs: type: git url: https://github.com/autowarefoundation/autoware_adapi_msgs.git diff --git a/map/autoware_map_projection_loader/README.md b/map/autoware_map_projection_loader/README.md index ad35a666eb0b8..1f9fe656c03af 100644 --- a/map/autoware_map_projection_loader/README.md +++ b/map/autoware_map_projection_loader/README.md @@ -70,6 +70,22 @@ map_origin: altitude: 0.0 # [m] ``` +### Using LocalCartesian + +If you want to use local cartesian WGS84, please specify the map origin as well. + +Currently LocalCartesian can only be used in lanelet2_map_loader, packages like gnss_poser doesn't support it right now. + +```yaml +# map_projector_info.yaml +projector_type: LocalCartesian +vertical_datum: WGS84 +map_origin: + latitude: 35.6762 # [deg] + longitude: 139.6503 # [deg] + altitude: 0.0 # [m] +``` + ### Using TransverseMercator If you want to use Transverse Mercator projection, please specify the map origin as well. diff --git a/map/autoware_map_projection_loader/src/map_projection_loader.cpp b/map/autoware_map_projection_loader/src/map_projection_loader.cpp index 981380d1d493b..1f175c8bf21d1 100644 --- a/map/autoware_map_projection_loader/src/map_projection_loader.cpp +++ b/map/autoware_map_projection_loader/src/map_projection_loader.cpp @@ -39,6 +39,7 @@ autoware_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & } else if ( msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM || + msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN || msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::TRANSVERSE_MERCATOR) { msg.vertical_datum = data["vertical_datum"].as(); msg.map_origin.latitude = data["map_origin"]["latitude"].as(); @@ -59,8 +60,9 @@ autoware_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & msg.projector_type = autoware_map_msgs::msg::MapProjectorInfo::LOCAL; } else { throw std::runtime_error( - "Invalid map projector type. Currently supported types: MGRS, LocalCartesianUTM, " - "TransverseMercator, and Local"); + "Invalid map projector type. Currently supported types: MGRS, LocalCartesian, " + "LocalCartesianUTM, " + "TransverseMercator, and local"); } return msg; }