62 bool setParams(
const std::string& name_space)
override;
64 bool initialize(
const rclcpp::Node::SharedPtr& node)
override;
65 void start()
override;
71 virtual void updateMask(
const sensor_msgs::msg::PointCloud2& cloud,
const Eigen::Vector3d& sensor_origin,
72 std::vector<int>& mask);
75 bool getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform)
const;
76 void cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
81 rclcpp::Node::SharedPtr node_;
83 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
84 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
87 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
90 std::string point_cloud_topic_;
94 unsigned int point_subsample_;
95 double max_update_rate_;
96 std::string filtered_cloud_topic_;
98 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
100 message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
101 tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
105 octomap::KeyRay key_ray_;
107 std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
108 std::vector<int> mask_;
110 rclcpp::Logger logger_;