Skip to content

Commit a186474

Browse files
StepTurtleMehmet Dogru
authored and
Mehmet Dogru
committed
Revize parameters
Signed-off-by: Barış Zeren <bzeren1819@gmail.com>
1 parent 9385646 commit a186474

File tree

4 files changed

+18
-12
lines changed

4 files changed

+18
-12
lines changed

launch/tier4_map_launch/launch/map.launch.xml

+9
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@
33
<arg name="pointcloud_map_path"/>
44
<arg name="pointcloud_map_metadata_path"/>
55
<arg name="lanelet2_map_path"/>
6+
<arg name="lanelet2_map_folder_path"/>
7+
<arg name="lanelet2_map_metadata_path"/>
68
<arg name="map_projector_info_path"/>
79

810
<!-- Parameter files -->
@@ -39,12 +41,19 @@
3941
<composable_node pkg="map_loader" plugin="Lanelet2MapLoaderNode" name="lanelet2_map_loader">
4042
<param from="$(var lanelet2_map_loader_param_path)"/>
4143
<param name="lanelet2_map_path" value="$(var lanelet2_map_path)"/>
44+
<param name="lanelet2_map_folder_path" value="[$(var lanelet2_map_folder_path)]"/>
45+
<param name="lanelet2_map_metadata_path" value="$(var lanelet2_map_metadata_path)"/>
4246
<remap from="output/lanelet2_map" to="vector_map"/>
47+
<remap from="service/get_differential_lanelet_map" to="/map/get_differential_lanelet_map"/>
4348
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
4449
</composable_node>
4550

4651
<composable_node pkg="autoware_dynamic_lanelet_provider" plugin="autoware::dynamic_lanelet_provider::DynamicLaneletProviderNode" name="dynamic_lanelet_provider">
4752
<param from="$(var dynamic_lanelet_provider_param_path)"/>
53+
<remap from="input/odometry" to="/localization/kinematic_state"/>
54+
<remap from="output/lanelet2_map" to="dynamic_vector_map"/>
55+
<remap from="service/get_differential_lanelet_map" to="/map/get_differential_lanelet_map"/>
56+
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
4857
</composable_node>
4958

5059
<composable_node pkg="map_loader" plugin="Lanelet2MapVisualizationNode" name="lanelet2_map_visualization">

map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp

+4-6
Original file line numberDiff line numberDiff line change
@@ -53,13 +53,14 @@ DynamicLaneletProviderNode::DynamicLaneletProviderNode(const rclcpp::NodeOptions
5353
timer_callback_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
5454

5555
dynamic_map_pub_ = this->create_publisher<autoware_auto_mapping_msgs::msg::HADMapBin>(
56-
"/map/dynamic_vector_map", rclcpp::QoS{1}.transient_local());
56+
"output/lanelet2_map", rclcpp::QoS{1}.transient_local());
5757

5858
map_loader_client_ = this->create_client<autoware_map_msgs::srv::GetDifferentialLanelet2Map>(
59-
"/map/get_differential_lanelet_map", rmw_qos_profile_services_default, client_callback_group_);
59+
"service/get_differential_lanelet_map", rmw_qos_profile_services_default,
60+
client_callback_group_);
6061

6162
odometry_sub_ = this->create_subscription<nav_msgs::msg::Odometry>(
62-
"/localization/kinematic_state", 100,
63+
"input/odometry", 100,
6364
std::bind(&DynamicLaneletProviderNode::onOdometry, this, std::placeholders::_1));
6465

6566
const auto projector_info_adaptor = component_interface_utils::NodeAdaptor(this);
@@ -173,9 +174,6 @@ void DynamicLaneletProviderNode::updateMap(const geometry_msgs::msg::Point & pos
173174
status = result.wait_for(std::chrono::seconds(1));
174175
}
175176

176-
autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr map_ptr{
177-
std::make_shared<autoware_auto_mapping_msgs::msg::HADMapBin const>(
178-
result.get()->differential_map)};
179177
dynamic_map_pub_->publish(result.get()->differential_map);
180178
}
181179

map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,7 @@ Lanelet2DifferentialLoaderModule::Lanelet2DifferentialLoaderModule(
4141
});
4242

4343
get_differential_lanelet2_maps_service_ = node->create_service<GetDifferentialLanelet2Map>(
44-
"/map/get_differential_lanelet_map",
44+
"service/get_differential_lanelet_map",
4545
std::bind(
4646
&Lanelet2DifferentialLoaderModule::onServiceGetDifferentialLanelet2Map, this,
4747
std::placeholders::_1, std::placeholders::_2));

map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -83,12 +83,11 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
8383
declare_parameter("lanelet2_map_path", "");
8484
declare_parameter("center_line_resolution");
8585

86-
bool tmp_differential_lanelet2_loading = true;
87-
std::vector<std::string> tmp_lanelet2_paths_or_directory = {
88-
"/home/bzeren/autoware_map/dummy_800_4/tmp_lanelet2_map.osm"};
86+
std::vector<std::string> tmp_lanelet2_paths_or_directory =
87+
declare_parameter<std::vector<std::string>>("lanelet2_map_folder_path");
8988
std::string tmp_lanelet2_map_metadata_path =
90-
"/home/bzeren/autoware_map/dummy_800_4/tmp_lanelet2_map_metadata.yaml";
91-
if (tmp_differential_lanelet2_loading) {
89+
declare_parameter<std::string>("lanelet2_map_metadata_path");
90+
if (declare_parameter<bool>("enabled_dynamic_lanelet_loading")) {
9291
std::map<std::string, Lanelet2FileMetaData> lanelet2_metadata_dict;
9392
try {
9493
lanelet2_metadata_dict = getLanelet2Metadata(

0 commit comments

Comments
 (0)