Skip to content

Commit 376ab61

Browse files
committed
fix: change ogm fusion node pub policy to reliable
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 4e5ef9c commit 376ab61

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

perception/probabilistic_occupancy_grid_map/src/fusion/synchronized_grid_map_fusion_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -112,9 +112,9 @@ GridMapFusionNode::GridMapFusionNode(const rclcpp::NodeOptions & node_options)
112112

113113
// pub grid_map
114114
fused_map_pub_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
115-
"~/output/occupancy_grid_map", rclcpp::QoS{1}.best_effort());
115+
"~/output/occupancy_grid_map", rclcpp::QoS{1}.reliable());
116116
single_frame_pub_ = this->create_publisher<nav_msgs::msg::OccupancyGrid>(
117-
"~/debug/single_frame_map", rclcpp::QoS{1}.best_effort());
117+
"~/debug/single_frame_map", rclcpp::QoS{1}.reliable());
118118

119119
// updater
120120
occupancy_grid_map_updater_ptr_ = std::make_shared<OccupancyGridMapLOBFUpdater>(

0 commit comments

Comments
 (0)