39 #include <rclcpp/rclcpp.hpp> 
   40 #include <rclcpp/callback_group.hpp> 
   41 #include <tf2_ros/transform_listener.h> 
   42 #include <tf2_ros/message_filter.h> 
   43 #include <message_filters/subscriber.h> 
   44 #include <sensor_msgs/msg/point_cloud2.hpp> 
   58   bool setParams(
const std::string& name_space) 
override;
 
   60   bool initialize(
const rclcpp::Node::SharedPtr& node) 
override;
 
   61   void start() 
override;
 
   68                           std::vector<int>& mask);
 
   71   bool getShapeTransform(
ShapeHandle h, Eigen::Isometry3d& transform) 
const;
 
   72   void cloudMsgCallback(
const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
 
   78   rclcpp::Node::SharedPtr node_;
 
   80   std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
 
   81   std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
 
   84   rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
 
   87   std::string point_cloud_topic_;
 
   91   unsigned int point_subsample_;
 
   92   double max_update_rate_;
 
   93   std::string filtered_cloud_topic_;
 
   95   rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
 
   97   message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
 
   98   tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
 
  102   octomap::KeyRay key_ray_;
 
  104   std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
 
  105   std::vector<int> mask_;
 
Base class for classes which update the occupancy map.
 
bool setParams(const std::string &name_space) override
Set updater params using struct that comes from parsing a yaml string. This must be called after setM...
 
PointCloudOctomapUpdater()
 
virtual void updateMask(const sensor_msgs::msg::PointCloud2 &cloud, const Eigen::Vector3d &sensor_origin, std::vector< int > &mask)
 
bool initialize(const rclcpp::Node::SharedPtr &node) override
Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams(...
 
void forgetShape(ShapeHandle handle) override
 
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
 
~PointCloudOctomapUpdater() override
 
Vec3fX< details::Vec3Data< double > > Vector3d