63 bool setParams(
const std::string& name_space)
override;
65 bool initialize(
const rclcpp::Node::SharedPtr& node)
override;
66 void start()
override;
72 virtual void updateMask(
const sensor_msgs::msg::PointCloud2& cloud,
const Eigen::Vector3d& sensor_origin,
73 std::vector<int>& mask);
76 bool getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform)
const;
77 void cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
82 rclcpp::Node::SharedPtr node_;
84 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
85 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
88 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
91 std::string point_cloud_topic_;
95 unsigned int point_subsample_;
96 double max_update_rate_;
97 std::string filtered_cloud_topic_;
99 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
101 message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
102 tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
106 octomap::KeyRay key_ray_;
108 std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
109 std::vector<int> mask_;
111 rclcpp::Logger logger_;