Skip to content

Commit

Permalink
Merge pull request #781 from tier4/sync-upstream
Browse files Browse the repository at this point in the history
chore: sync upstream
  • Loading branch information
tier4-autoware-public-bot[bot] authored Aug 31, 2023
2 parents 70f0656 + 053d31f commit a37ef72
Show file tree
Hide file tree
Showing 35 changed files with 879 additions and 353 deletions.
35 changes: 35 additions & 0 deletions common/geography_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
cmake_minimum_required(VERSION 3.14)
project(geography_utils)

find_package(autoware_cmake REQUIRED)
autoware_package()

# GeographicLib
find_package(PkgConfig)
find_path(GeographicLib_INCLUDE_DIR GeographicLib/Config.h
PATH_SUFFIXES GeographicLib
)
set(GeographicLib_INCLUDE_DIRS ${GeographicLib_INCLUDE_DIR})
find_library(GeographicLib_LIBRARIES NAMES Geographic)

ament_auto_add_library(geography_utils SHARED
src/height.cpp
)

target_link_libraries(geography_utils
${GeographicLib_LIBRARIES}
)

if(BUILD_TESTING)
find_package(ament_cmake_ros REQUIRED)

file(GLOB_RECURSE test_files test/*.cpp)

ament_add_ros_isolated_gtest(test_geography_utils ${test_files})

target_link_libraries(test_geography_utils
geography_utils
)
endif()

ament_auto_package()
5 changes: 5 additions & 0 deletions common/geography_utils/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# geography_utils

## Purpose

This package contains geography-related functions used by other packages, so please refer to them as needed.
36 changes: 36 additions & 0 deletions common/geography_utils/include/geography_utils/height.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef GEOGRAPHY_UTILS__HEIGHT_HPP_
#define GEOGRAPHY_UTILS__HEIGHT_HPP_

#include <map>
#include <stdexcept>
#include <string>
#include <utility>

namespace geography_utils
{

typedef double (*HeightConversionFunction)(
const double height, const double latitude, const double longitude);
double convert_wgs84_to_egm2008(const double height, const double latitude, const double longitude);
double convert_egm2008_to_wgs84(const double height, const double latitude, const double longitude);
double convert_height(
const double height, const double latitude, const double longitude,
const std::string & source_vertical_datum, const std::string & target_vertical_datum);

} // namespace geography_utils

#endif // GEOGRAPHY_UTILS__HEIGHT_HPP_
22 changes: 22 additions & 0 deletions common/geography_utils/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>geography_utils</name>
<version>0.1.0</version>
<description>The geography_utils package</description>
<maintainer email="[email protected]">Koji Minoda</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>geographiclib</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
63 changes: 63 additions & 0 deletions common/geography_utils/src/height.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <GeographicLib/Geoid.hpp>
#include <geography_utils/height.hpp>

#include <map>
#include <stdexcept>
#include <string>
#include <utility>

namespace geography_utils
{

double convert_wgs84_to_egm2008(const double height, const double latitude, const double longitude)
{
GeographicLib::Geoid egm2008("egm2008-1");
// cSpell: ignore ELLIPSOIDTOGEOID
return egm2008.ConvertHeight(latitude, longitude, height, GeographicLib::Geoid::ELLIPSOIDTOGEOID);
}

double convert_egm2008_to_wgs84(const double height, const double latitude, const double longitude)
{
GeographicLib::Geoid egm2008("egm2008-1");
// cSpell: ignore GEOIDTOELLIPSOID
return egm2008.ConvertHeight(latitude, longitude, height, GeographicLib::Geoid::GEOIDTOELLIPSOID);
}

double convert_height(
const double height, const double latitude, const double longitude,
const std::string & source_vertical_datum, const std::string & target_vertical_datum)
{
if (source_vertical_datum == target_vertical_datum) {
return height;
}
std::map<std::pair<std::string, std::string>, HeightConversionFunction> conversion_map;
conversion_map[{"WGS84", "EGM2008"}] = convert_wgs84_to_egm2008;
conversion_map[{"EGM2008", "WGS84"}] = convert_egm2008_to_wgs84;

auto key = std::make_pair(source_vertical_datum, target_vertical_datum);
if (conversion_map.find(key) != conversion_map.end()) {
return conversion_map[key](height, latitude, longitude);
} else {
std::string error_message =
"Invalid conversion types: " + std::string(source_vertical_datum.c_str()) + " to " +
std::string(target_vertical_datum.c_str());

throw std::invalid_argument(error_message);
}
}

} // namespace geography_utils
92 changes: 92 additions & 0 deletions common/geography_utils/test/test_height.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <geography_utils/height.hpp>

#include <gtest/gtest.h>

#include <stdexcept>
#include <string>

// Test case to verify if same source and target datums return original height
TEST(Tier4GeographyUtils, SameSourceTargetDatum)
{
const double height = 10.0;
const double latitude = 35.0;
const double longitude = 139.0;
const std::string datum = "WGS84";

double converted_height =
geography_utils::convert_height(height, latitude, longitude, datum, datum);

EXPECT_DOUBLE_EQ(height, converted_height);
}

// Test case to verify valid source and target datums
TEST(Tier4GeographyUtils, ValidSourceTargetDatum)
{
// Calculated with
// https://www.unavco.org/software/geodetic-utilities/geoid-height-calculator/geoid-height-calculator.html
const double height = 10.0;
const double latitude = 35.0;
const double longitude = 139.0;
const double target_height = -30.18;

double converted_height =
geography_utils::convert_height(height, latitude, longitude, "WGS84", "EGM2008");

EXPECT_NEAR(target_height, converted_height, 0.1);
}

// Test case to verify invalid source and target datums
TEST(Tier4GeographyUtils, InvalidSourceTargetDatum)
{
const double height = 10.0;
const double latitude = 35.0;
const double longitude = 139.0;

EXPECT_THROW(
geography_utils::convert_height(height, latitude, longitude, "INVALID1", "INVALID2"),
std::invalid_argument);
}

// Test case to verify invalid source datums
TEST(Tier4GeographyUtils, InvalidSourceDatum)
{
const double height = 10.0;
const double latitude = 35.0;
const double longitude = 139.0;

EXPECT_THROW(
geography_utils::convert_height(height, latitude, longitude, "INVALID1", "WGS84"),
std::invalid_argument);
}

// Test case to verify invalid target datums
TEST(Tier4GeographyUtils, InvalidTargetDatum)
{
const double height = 10.0;
const double latitude = 35.0;
const double longitude = 139.0;

EXPECT_THROW(
geography_utils::convert_height(height, latitude, longitude, "WGS84", "INVALID2"),
std::invalid_argument);
}

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <Eigen/Core>
#include <Eigen/Geometry>

#include <lanelet2_core/LaneletMap.h>
#ifdef ROS_DISTRO_GALACTIC
#include <tf2_eigen/tf2_eigen.h>
#else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <lanelet2_core/geometry/Lanelet.h>
#include <lanelet2_core/primitives/LaneletSequence.h>
#include <lanelet2_io/Io.h>
#include <lanelet2_routing/RoutingGraph.h>

#include <iostream>
#include <unordered_set>
Expand Down
1 change: 1 addition & 0 deletions perception/map_based_prediction/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<maintainer email="[email protected]">Shunsuke Miura</maintainer>
<maintainer email="[email protected]">Yoshi Ri</maintainer>
<maintainer email="[email protected]">Takayuki Murooka</maintainer>
<maintainer email="[email protected]">Kyoichi Sugahara</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
Expand Down
10 changes: 5 additions & 5 deletions perception/radar_fusion_to_detected_object/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,11 +13,11 @@ The document of core algorithm is [here](docs/algorithm.md)

### Parameters for sensor fusion

| Name | Type | Description | Default value |
| :----------------------- | :----- | :------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
| bounding_box_margin | double | The distance to extend the 2D bird's-eye view Bounding Box on each side. This distance is used as a threshold to find radar centroids falling inside the extended box. [m] | 2.0 |
| split_threshold_velocity | double | The object's velocity threshold to decide to split for two objects from radar information (currently not implemented) [m/s] | 5.0 |
| threshold_yaw_diff | double | The yaw orientation threshold. If $ \vert \theta _{ob} - \theta_ {ra} \vert < threshold*yaw_diff $ attached to radar information include estimated velocity, where $ \theta*{ob} $ is yaw angle from 3d detected object, $ \theta\_ {ra} $ is yaw angle from radar object. [rad] | 0.35 |
| Name | Type | Description | Default value |
| :----------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
| bounding_box_margin | double | The distance to extend the 2D bird's-eye view Bounding Box on each side. This distance is used as a threshold to find radar centroids falling inside the extended box. [m] | 2.0 |
| split_threshold_velocity | double | The object's velocity threshold to decide to split for two objects from radar information (currently not implemented) [m/s] | 5.0 |
| threshold_yaw_diff | double | The yaw orientation threshold. If *θob**θra*< threshold × yaw*diff attached to radar information include estimated velocity, where*θob*is yaw angle from 3d detected object,*θra\_ is yaw angle from radar object. [rad] | 0.35 |

### Weight parameters for velocity estimation

Expand Down
Loading

0 comments on commit a37ef72

Please sign in to comment.