70 bool setParams(
const std::string& name_space)
override;
72 bool initialize(
const rclcpp::Node::SharedPtr& node)
override;
73 void start()
override;
79 virtual void updateMask(
const sensor_msgs::msg::PointCloud2& cloud,
const Eigen::Vector3d& sensor_origin,
80 std::vector<int>& mask);
83 bool getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform)
const;
84 void cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
89 rclcpp::Node::SharedPtr node_;
91 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
92 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
95 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
98 std::string point_cloud_topic_;
102 unsigned int point_subsample_;
103 double max_update_rate_;
104 std::string filtered_cloud_topic_;
106 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
108 message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
109 tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
113 octomap::KeyRay key_ray_;
115 std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
116 std::vector<int> mask_;
118 rclcpp::Logger logger_;