Skip to content
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

fix(gnss_poser): added local coordinate system in UTM to gnss_poser #1227

Merged
merged 14 commits into from
Jul 20, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
Prev Previous commit
Next Next commit
ci(pre-commit): autofix
  • Loading branch information
pre-commit-ci[bot] authored and ataparlar committed Jul 20, 2022
commit 467c02877c0cceea43da7159ec36029036a435f4
2 changes: 1 addition & 1 deletion sensing/gnss_poser/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ The `gnss_poser` is a node that subscribes gnss sensing messages and calculates
### Core Parameters

| Name | Type | Default Value | Description |
| -------------------- | ------ | ---------------- |-------------------------------------------------------------------------------------------------------------------------------------------------------|
| -------------------- | ------ | ---------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------- |
| `base_frame` | string | "base_link" | frame d |
| `gnss_frame` | string | "gnss" | frame id |
| `gnss_base_frame` | string | "gnss_base_link" | frame id |
Expand Down
14 changes: 7 additions & 7 deletions sensing/gnss_poser/include/gnss_poser/convert.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,15 +113,15 @@ GNSSStat NavSatFix2LocalCartesianUTM(
double global_y;
try {
if (utm_origin_needs_init) {
GeographicLib::UTMUPS::Forward(
nav_sat_fix_origin_.latitude, nav_sat_fix_origin_.longitude, utm_origin.zone,
utm_origin.northup, utm_origin.x, utm_origin.y);
utm_origin.z = EllipsoidHeight2OrthometricHeight(nav_sat_fix_msg, logger);
utm_origin_needs_init = false;
GeographicLib::UTMUPS::Forward(
nav_sat_fix_origin_.latitude, nav_sat_fix_origin_.longitude, utm_origin.zone,
utm_origin.northup, utm_origin.x, utm_origin.y);
utm_origin.z = EllipsoidHeight2OrthometricHeight(nav_sat_fix_msg, logger);
utm_origin_needs_init = false;
}
GeographicLib::UTMUPS::Forward(
nav_sat_fix_msg.latitude, nav_sat_fix_msg.longitude, utm_origin.zone, utm_origin.northup,
global_x, global_y);
nav_sat_fix_msg.latitude, nav_sat_fix_msg.longitude, utm_origin.zone, utm_origin.northup,
global_x, global_y);
utm_local.latitude = nav_sat_fix_msg.latitude;
utm_local.longitude = nav_sat_fix_msg.longitude;
utm_local.altitude = nav_sat_fix_msg.altitude;
Expand Down