Skip to content

feat(map_projection_loader): add scale_factor and remove altitude #340

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Merged
Show file tree
Hide file tree
Changes from 24 commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -76,12 +76,13 @@ jobs:

- name: Run clang-tidy
if: ${{ steps.get-changed-files.outputs.changed-files != '' }}
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
uses: autowarefoundation/autoware-github-actions/clang-tidy@feat/clang-tidy-underlay-workspace
with:
rosdistro: humble
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
target-files: ${{ steps.get-changed-files.outputs.changed-files }}
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy-ci
underlay-workspace: /opt/autoware

- name: Show disk space after the tasks
run: df -h
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@ std::unique_ptr<lanelet::Projector> get_lanelet2_projector(const MapProjectorInf
projector_info.map_origin.latitude, projector_info.map_origin.longitude,
projector_info.map_origin.altitude};
const lanelet::Origin origin{position};
const lanelet::projection::TransverseMercatorProjector projector{origin};
const lanelet::projection::TransverseMercatorProjector projector{
origin, projector_info.scale_factor};
return std::make_unique<lanelet::projection::TransverseMercatorProjector>(projector);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ TEST(GeographyUtilsLanelet2Projector, GetTransverseMercatorProjector)
projector_info.map_origin.latitude = 35.62426;
projector_info.map_origin.longitude = 139.74252;
projector_info.map_origin.altitude = 0.0;
projector_info.scale_factor = 0.9996;

std::unique_ptr<lanelet::Projector> projector =
autoware::geography_utils::get_lanelet2_projector(projector_info);
Expand Down
13 changes: 10 additions & 3 deletions map/autoware_map_projection_loader/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ There are three types of transformations from latitude and longitude to XYZ coor
projector_type: Local
```

Note that even if you input scale_factor, it will be overwritten to 1.0.

#### Limitation

The functionality that requires latitude and longitude will become unavailable.
Expand All @@ -52,6 +54,8 @@ vertical_datum: WGS84
mgrs_grid: 54SUE
```

Note that even if you input scale_factor, it will be overwritten to 0.9996.

#### Limitation

It cannot be used with maps that span across two or more MGRS grids. Please use it only when it falls within the scope of a single MGRS grid.
Expand All @@ -67,9 +71,10 @@ vertical_datum: WGS84
map_origin:
latitude: 35.6762 # [deg]
longitude: 139.6503 # [deg]
altitude: 0.0 # [m]
```

Note that even if you input scale_factor, it will be overwritten to 0.9996.

### Using LocalCartesian

If you want to use local cartesian WGS84, please specify the map origin as well.
Expand All @@ -83,12 +88,14 @@ vertical_datum: WGS84
map_origin:
latitude: 35.6762 # [deg]
longitude: 139.6503 # [deg]
altitude: 0.0 # [m]
```

Note that even if you input scale_factor, it will be overwritten to 1.0.

### Using TransverseMercator

If you want to use Transverse Mercator projection, please specify the map origin as well.
And specify the scale_factor of the map. If you didn't specify the scale_factor, it will be set 0.9996 as default value.

```yaml
# map_projector_info.yaml
Expand All @@ -97,7 +104,7 @@ vertical_datum: WGS84
map_origin:
latitude: 35.6762 # [deg]
longitude: 139.6503 # [deg]
altitude: 0.0 # [m]
scale_factor: 0.9996
```

## Published Topics
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
msg.vertical_datum = data["vertical_datum"].as<std::string>();
msg.map_origin.latitude = data["map_origin"]["latitude"].as<double>();
msg.map_origin.longitude = data["map_origin"]["longitude"].as<double>();
msg.map_origin.altitude = data["map_origin"]["altitude"].as<double>();
msg.map_origin.altitude = 0.0;

} else if (msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL) {
; // do nothing
Expand All @@ -64,6 +64,30 @@
"LocalCartesianUTM, "
"TransverseMercator, and local");
}

// set scale factor
static constexpr float scale_factor_for_utm = 0.9996;
static constexpr float scale_factor_for_local = 1.0;
if (msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::TRANSVERSE_MERCATOR) {
if (data["scale_factor"]) {
msg.scale_factor = data["scale_factor"].as<float>();
} else {
msg.scale_factor = scale_factor_for_utm;
}
} else if (
msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::MGRS ||
msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN_UTM) {
msg.scale_factor = scale_factor_for_utm;
} else if (
msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL ||
msg.projector_type == autoware_map_msgs::msg::MapProjectorInfo::LOCAL_CARTESIAN) {
msg.scale_factor = scale_factor_for_local;
}

if (msg.scale_factor <= 0.0) {
throw std::runtime_error(
"Invalid scale factor. The scale factor must be a value greater than 0.");

Check warning on line 89 in map/autoware_map_projection_loader/src/map_projection_loader.cpp

View check run for this annotation

Codecov / codecov/patch

map/autoware_map_projection_loader/src/map_projection_loader.cpp#L89

Added line #L89 was not covered by tests
}
return msg;
}

Expand Down Expand Up @@ -104,10 +128,8 @@
load_map_projector_info(yaml_filename, lanelet2_map_filename);

// Publish the message
MapProjectorInfo map_projector_info_specs;
publisher_ = this->create_publisher<MapProjectorInfo::Message>(
map_projector_info_specs.name,
autoware::component_interface_specs::get_qos(map_projector_info_specs));
MapProjectorInfo::name, autoware::component_interface_specs::get_qos(MapProjectorInfo{}));
publisher_->publish(msg);
}
} // namespace autoware::map_projection_loader
Expand Down
Loading