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

refactor(map_projection_loader)!: prefix package and namespace with autoware #8420

Merged
Show file tree
Hide file tree
Changes from all commits
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
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ localization/yabloc/yabloc_particle_filter/** anh.nguyen.2@tier4.jp kento.yabuuc
localization/yabloc/yabloc_pose_initializer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/map_height_fitter/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/map_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/autoware_map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/autoware_map_tf_generator/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/util/lanelet2_map_preprocessor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
perception/autoware_bytetrack/** manato.hirabayashi@tier4.jp yoshi.ri@tier4.jp
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_map_launch/launch/map.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@
<param name="pointcloud_map_path" value="$(var pointcloud_map_path)"/>
</node>

<include file="$(find-pkg-share map_projection_loader)/launch/map_projection_loader.launch.xml">
<include file="$(find-pkg-share autoware_map_projection_loader)/launch/map_projection_loader.launch.xml">
<arg name="param_path" value="$(var map_projection_loader_param_path)"/>
<arg name="map_projector_info_path" value="$(var map_projector_info_path)"/>
<arg name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_map_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_map_projection_loader</exec_depend>
<exec_depend>autoware_map_tf_generator</exec_depend>
<exec_depend>map_loader</exec_depend>
<exec_depend>map_projection_loader</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(map_projection_loader)
project(autoware_map_projection_loader)

find_package(autoware_cmake REQUIRED)
autoware_package()
Expand All @@ -12,7 +12,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "MapProjectionLoader"
PLUGIN "autoware::map_projection_loader::MapProjectionLoader"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR SingleThreadedExecutor
)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# map_projection_loader
# autoware_map_projection_loader

## Feature

`map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating.
`autoware_map_projection_loader` is responsible for publishing `map_projector_info` that defines in which kind of coordinate Autoware is operating.
This is necessary information especially when you want to convert from global (geoid) to local coordinate or the other way around.

- If `map_projector_info_path` DOES exist, this node loads it and publishes the map projection information accordingly.
Expand Down Expand Up @@ -92,4 +92,4 @@ map_origin:

Note that these parameters are assumed to be passed from launch arguments, and it is not recommended to directly write them in `map_projection_loader.param.yaml`.

{{ json_to_markdown("map/map_projection_loader/schema/map_projection_loader.schema.json") }}
{{ json_to_markdown("map/autoware_map_projection_loader/schema/map_projection_loader.schema.json") }}
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_
#define MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_
#ifndef AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_
#define AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_

#include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp>
#include <autoware_lanelet2_extension/projection/mgrs_projector.hpp>
Expand All @@ -24,6 +24,9 @@

#include <string>

namespace autoware::map_projection_loader
{
tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename);
} // namespace autoware::map_projection_loader

#endif // MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_
#endif // AUTOWARE__MAP_PROJECTION_LOADER__LOAD_INFO_FROM_LANELET2_MAP_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_
#define MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_
#ifndef AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_
#define AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_

#include "rclcpp/rclcpp.hpp"

Expand All @@ -22,6 +22,8 @@

#include <string>

namespace autoware::map_projection_loader
{
tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename);
tier4_map_msgs::msg::MapProjectorInfo load_map_projector_info(
const std::string & yaml_filename, const std::string & lanelet2_map_filename);
Expand All @@ -35,5 +37,6 @@ class MapProjectionLoader : public rclcpp::Node
using MapProjectorInfo = map_interface::MapProjectorInfo;
component_interface_utils::Publisher<MapProjectorInfo>::SharedPtr publisher_;
};
} // namespace autoware::map_projection_loader

#endif // MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_
#endif // AUTOWARE__MAP_PROJECTION_LOADER__MAP_PROJECTION_LOADER_HPP_
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
<launch>
<arg name="param_path" default="$(find-pkg-share map_projection_loader)/config/map_projection_loader.param.yaml"/>
<arg name="param_path" default="$(find-pkg-share autoware_map_projection_loader)/config/map_projection_loader.param.yaml"/>

<arg name="map_projector_info_path" description="Path to the yaml file"/>
<arg name="lanelet2_map_path" description="Path to the lanelet2 map file"/>

<node pkg="map_projection_loader" exec="map_projection_loader_node" output="both">
<node pkg="autoware_map_projection_loader" exec="autoware_map_projection_loader_node" output="both">
<param from="$(var param_path)" allow_substs="true"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?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>map_projection_loader</name>
<name>autoware_map_projection_loader</name>
<version>0.1.0</version>
<description>map_projection_loader package as a ROS 2 node</description>
<description>autoware_map_projection_loader package as a ROS 2 node</description>
<maintainer email="yamato.ando@tier4.jp">Yamato Ando</maintainer>
<maintainer email="masahiro.sakamoto@tier4.jp">Masahiro Sakamoto</maintainer>
<maintainer email="kento.yabuuchi.2@tier4.jp">Kento Yabuuchi</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp"

#include "tier4_map_msgs/msg/map_projector_info.hpp"

Expand All @@ -23,6 +23,8 @@

#include <string>

namespace autoware::map_projection_loader
{
tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::string & filename)
{
lanelet::ErrorMessages errors{};
Expand Down Expand Up @@ -58,3 +60,4 @@ tier4_map_msgs::msg::MapProjectorInfo load_info_from_lanelet2_map(const std::str
msg.vertical_datum = tier4_map_msgs::msg::MapProjectorInfo::WGS84;
return msg;
}
} // namespace autoware::map_projection_loader
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "map_projection_loader/map_projection_loader.hpp"
#include "autoware/map_projection_loader/map_projection_loader.hpp"

#include "map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp"

#include <tier4_map_msgs/msg/map_projector_info.hpp>

Expand All @@ -23,6 +23,8 @@
#include <filesystem>
#include <fstream>

namespace autoware::map_projection_loader
{
tier4_map_msgs::msg::MapProjectorInfo load_info_from_yaml(const std::string & filename)
{
YAML::Node data = YAML::LoadFile(filename);
Expand Down Expand Up @@ -93,6 +95,7 @@ MapProjectionLoader::MapProjectionLoader(const rclcpp::NodeOptions & options)
adaptor.init_pub(publisher_);
publisher_->publish(msg);
}
} // namespace autoware::map_projection_loader

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(MapProjectionLoader)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_projection_loader::MapProjectionLoader)
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp"

#include <GeographicLib/MGRS.hpp>
#include <GeographicLib/UTMUPS.hpp>
Expand Down Expand Up @@ -92,7 +92,8 @@ TEST(TestLoadFromLanelet2Map, LoadMGRSGrid)
save_dummy_mgrs_lanelet2_map(mgrs_coord, output_path);

// Test the function
const auto projector_info = load_info_from_lanelet2_map(output_path);
const auto projector_info =
autoware::map_projection_loader::load_info_from_lanelet2_map(output_path);

// Check the result
EXPECT_EQ(projector_info.projector_type, "MGRS");
Expand All @@ -106,7 +107,8 @@ TEST(TestLoadFromLanelet2Map, LoadLocalGrid)
save_dummy_local_lanelet2_map(output_path);

// Test the function
const auto projector_info = load_info_from_lanelet2_map(output_path);
const auto projector_info =
autoware::map_projection_loader::load_info_from_lanelet2_map(output_path);

// Check the result
EXPECT_EQ(projector_info.projector_type, "local");
Expand All @@ -119,7 +121,8 @@ TEST(TestLoadFromLanelet2Map, LoadNoLocalGrid)
save_dummy_mgrs_lanelet2_map_with_one_zero_point(output_path);

// Test the function
const auto projector_info = load_info_from_lanelet2_map(output_path);
const auto projector_info =
autoware::map_projection_loader::load_info_from_lanelet2_map(output_path);

// Check the result
EXPECT_EQ(projector_info.projector_type, "MGRS");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,12 @@
@pytest.mark.launch_test
def generate_test_description():
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)

map_projection_loader_node = Node(
package="map_projection_loader",
executable="map_projection_loader_node",
package="autoware_map_projection_loader",
executable="autoware_map_projection_loader_node",
output="screen",
parameters=[
{
Expand Down Expand Up @@ -122,7 +122,7 @@ def test_node_link(self):

# Load the yaml file directly
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)
with open(map_projector_info_path) as f:
yaml_data = yaml.load(f, Loader=yaml.FullLoader)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,12 @@
@pytest.mark.launch_test
def generate_test_description():
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)

map_projection_loader_node = Node(
package="map_projection_loader",
executable="map_projection_loader_node",
package="autoware_map_projection_loader",
executable="autoware_map_projection_loader_node",
output="screen",
parameters=[
{
Expand Down Expand Up @@ -122,7 +122,7 @@ def test_node_link(self):

# Load the yaml file directly
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)
with open(map_projector_info_path) as f:
yaml_data = yaml.load(f, Loader=yaml.FullLoader)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,12 @@
@pytest.mark.launch_test
def generate_test_description():
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)

map_projection_loader_node = Node(
package="map_projection_loader",
executable="map_projection_loader_node",
package="autoware_map_projection_loader",
executable="autoware_map_projection_loader_node",
output="screen",
parameters=[
{
Expand Down Expand Up @@ -122,7 +122,7 @@ def test_node_link(self):

# Load the yaml file directly
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)
with open(map_projector_info_path) as f:
yaml_data = yaml.load(f, Loader=yaml.FullLoader)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,12 @@
@pytest.mark.launch_test
def generate_test_description():
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)

map_projection_loader_node = Node(
package="map_projection_loader",
executable="map_projection_loader_node",
package="autoware_map_projection_loader",
executable="autoware_map_projection_loader_node",
output="screen",
parameters=[
{
Expand Down Expand Up @@ -122,7 +122,7 @@ def test_node_link(self):

# Load the yaml file directly
map_projector_info_path = os.path.join(
get_package_share_directory("map_projection_loader"), YAML_FILE_PATH
get_package_share_directory("autoware_map_projection_loader"), YAML_FILE_PATH
)
with open(map_projector_info_path) as f:
yaml_data = yaml.load(f, Loader=yaml.FullLoader)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>autoware_geography_utils</depend>
<depend>autoware_lanelet2_extension</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_map_projection_loader</depend>
<depend>autoware_mission_planner</depend>
<depend>autoware_motion_utils</depend>
<depend>autoware_path_optimizer</depend>
Expand All @@ -32,7 +33,6 @@
<depend>global_parameter_loader</depend>
<depend>interpolation</depend>
<depend>map_loader</depend>
<depend>map_projection_loader</depend>
<depend>osqp_interface</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "static_centerline_generator_node.hpp"

#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "autoware/map_projection_loader/map_projection_loader.hpp"
#include "autoware/motion_utils/resample/resample.hpp"
#include "autoware/motion_utils/trajectory/conversion.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
Expand All @@ -25,8 +27,6 @@
#include "centerline_source/bag_ego_trajectory_based_centerline.hpp"
#include "interpolation/spline_interpolation_points_2d.hpp"
#include "map_loader/lanelet2_map_loader_node.hpp"
#include "map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "map_projection_loader/map_projection_loader.hpp"
#include "type_alias.hpp"
#include "utils.hpp"

Expand Down Expand Up @@ -370,8 +370,8 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_
// load map by the map_loader package
map_bin_ptr_ = [&]() -> LaneletMapBin::ConstSharedPtr {
// load map
map_projector_info_ =
std::make_unique<MapProjectorInfo>(load_info_from_lanelet2_map(lanelet2_input_file_path));
map_projector_info_ = std::make_unique<MapProjectorInfo>(
autoware::map_projection_loader::load_info_from_lanelet2_map(lanelet2_input_file_path));
const auto map_ptr =
Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_);
if (!map_ptr) {
Expand Down
Loading