Skip to content

Commit 278fafe

Browse files
committed
feat(map): add launch_pointcloud_map_loader
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 9313a4c commit 278fafe

File tree

2 files changed

+7
-3
lines changed

2 files changed

+7
-3
lines changed

launch/tier4_map_launch/launch/map.launch.xml

+4-1
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,14 @@
1717
<let name="container_type" value="component_container" unless="$(var use_multithread)"/>
1818
<let name="container_type" value="component_container_mt" if="$(var use_multithread)"/>
1919

20+
<!-- whether use pointcloud map -->
21+
<arg name="launch_pointcloud_map_loader" default="true" description="launch pointcloud map loader"/>
22+
2023
<group>
2124
<push-ros-namespace namespace="map"/>
2225

2326
<node_container pkg="rclcpp_components" exec="$(var container_type)" name="map_container" namespace="" output="screen">
24-
<composable_node pkg="map_loader" plugin="PointCloudMapLoaderNode" name="pointcloud_map_loader">
27+
<composable_node pkg="map_loader" plugin="PointCloudMapLoaderNode" name="pointcloud_map_loader" if="$(var launch_pointcloud_map_loader)">
2528
<param from="$(var pointcloud_map_loader_param_path)"/>
2629
<param name="pcd_paths_or_directory" value="[$(var pointcloud_map_path)]"/>
2730
<param name="pcd_metadata_path" value="$(var pointcloud_map_metadata_path)"/>

map/map_height_fitter/src/map_height_fitter.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -72,8 +72,9 @@ MapHeightFitter::Impl::Impl(rclcpp::Node * node) : tf2_listener_(tf2_buffer_), n
7272

7373
const auto map_loader_name = node->declare_parameter<std::string>("map_loader_name");
7474
params_map_loader_ = rclcpp::AsyncParametersClient::make_shared(node, map_loader_name);
75-
params_map_loader_->wait_for_service();
76-
params_map_loader_->get_parameters({enable_partial_load}, callback);
75+
if (params_map_loader_->wait_for_service(std::chrono::seconds(5.0))) {
76+
params_map_loader_->get_parameters({enable_partial_load}, callback);
77+
}
7778
}
7879

7980
void MapHeightFitter::Impl::on_map(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)

0 commit comments

Comments
 (0)