Skip to content

Commit c0e777a

Browse files
takam5f2pre-commit-ci-lite[bot]yukkysaito
authored
chore(occpancy_grid_outlier_filter): change obstacle_segmentation/pointcloud QoS (#12103)
* chore(occpancy_grid_outlier_filter): change obstacle_segmentation/pointcloud qos. Signed-off-by: Takayuki AKAMINE <takayuki.akamine@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Takayuki AKAMINE <takayuki.akamine@tier4.jp> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com> Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com>
1 parent 27fff5b commit c0e777a

1 file changed

Lines changed: 9 additions & 1 deletion

File tree

perception/autoware_occupancy_grid_map_outlier_filter/src/occupancy_grid_map_outlier_filter_node.cpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,15 @@ OccupancyGridMapOutlierFilterComponent::OccupancyGridMapOutlierFilterComponent(
254254
std::bind(
255255
&OccupancyGridMapOutlierFilterComponent::onOccupancyGridMapAndPointCloud2, this,
256256
std::placeholders::_1, std::placeholders::_2));
257-
pointcloud_pub_ = create_publisher<PointCloud2>("~/output/pointcloud", rclcpp::SensorDataQoS());
257+
258+
/**
259+
* To avoid data loss and simplify the operation, the hard coded QoS setting as Reliable is used
260+
* for the publisher of obstacle_segmentation/pointcloud. If there is a clear distinction between
261+
* data collection and autonomous driving modes, PublisherOptions with
262+
* QosOverridingOptions::with_default_policies should be good options instead of hard-coding QoS
263+
* setting.
264+
*/
265+
pointcloud_pub_ = create_publisher<PointCloud2>("~/output/pointcloud", rclcpp::QoS{5}.reliable());
258266

259267
/* Radius search 2d filter */
260268
if (use_radius_search_2d_filter) {

0 commit comments

Comments
 (0)