@@ -84,10 +84,13 @@ class BasicGraspingPerception : public rclcpp::Node
8484 {
8585 rclcpp::QoS qos (1 );
8686 qos.best_effort ();
87+ // Allow overriding QoS
88+ rclcpp::PublisherOptions pub_opts;
89+ pub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies ();
8790 object_cloud_pub_ =
88- this ->create_publisher <sensor_msgs::msg::PointCloud2>(" object_cloud" , qos);
91+ this ->create_publisher <sensor_msgs::msg::PointCloud2>(" object_cloud" , qos, pub_opts );
8992 support_cloud_pub_ =
90- this ->create_publisher <sensor_msgs::msg::PointCloud2>(" support_cloud" , qos);
93+ this ->create_publisher <sensor_msgs::msg::PointCloud2>(" support_cloud" , qos, pub_opts );
9194 }
9295
9396 // Range filter for cloud
@@ -101,10 +104,14 @@ class BasicGraspingPerception : public rclcpp::Node
101104 // Subscribe to head camera cloud
102105 rclcpp::QoS points_qos (10 );
103106 points_qos.best_effort ();
107+ // Allow overriding QoS
108+ rclcpp::SubscriptionOptions sub_opts;
109+ sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies ();
104110 cloud_sub_ = this ->create_subscription <sensor_msgs::msg::PointCloud2>(
105111 " /head_camera/depth_registered/points" ,
106112 points_qos,
107- std::bind (&BasicGraspingPerception::cloud_callback, this , _1));
113+ std::bind (&BasicGraspingPerception::cloud_callback, this , _1),
114+ sub_opts);
108115
109116 // Setup actionlib server
110117 server_ = rclcpp_action::create_server<FindGraspableObjectsAction>(
0 commit comments