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

fix: OctoMap and Filtered_Cloud Not Updating During Movement Execution (backport #3209) #3211

Merged
merged 6 commits into from
Jan 12, 2025
Merged
Show file tree
Hide file tree
Changes from 5 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
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#pragma once

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/callback_group.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/message_filter.h>
#include <message_filters/subscriber.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,8 +115,12 @@ void PointCloudOctomapUpdater::start()

if (point_cloud_subscriber_)
return;

rclcpp::SubscriptionOptions options;
options.callback_group = node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
/* subscribe to point cloud topic using tf filter*/
point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(node_, point_cloud_topic_);
point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(
node_, point_cloud_topic_, rmw_qos_profile_sensor_data, options);
if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty())
{
point_cloud_filter_ = new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
Expand Down
Loading