moveit2
The MoveIt Motion Planning Framework for ROS 2.
pointcloud_octomap_updater.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jon Binney, Ioan Sucan */
36 
37 #pragma once
38 
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>
47 
48 #include <memory>
49 
50 namespace occupancy_map_monitor
51 {
53 {
54 public:
56  ~PointCloudOctomapUpdater() override;
57 
58  bool setParams(const std::string& name_space) override;
59 
60  bool initialize(const rclcpp::Node::SharedPtr& node) override;
61  void start() override;
62  void stop() override;
63  ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) override;
64  void forgetShape(ShapeHandle handle) override;
65 
66 protected:
67  virtual void updateMask(const sensor_msgs::msg::PointCloud2& cloud, const Eigen::Vector3d& sensor_origin,
68  std::vector<int>& mask);
69 
70 private:
71  bool getShapeTransform(ShapeHandle h, Eigen::Isometry3d& transform) const;
72  void cloudMsgCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
73  void stopHelper();
74 
75  // TODO: Enable private node for publishing filtered point cloud
76  // ros::NodeHandle root_nh_;
77  // ros::NodeHandle private_nh_;
78  rclcpp::Node::SharedPtr node_;
79 
80  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
81  std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
82 
83  // Initialize clock type to RCL_ROS_TIME to prevent exception about time sources mismatch
84  rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
85 
86  /* params */
87  std::string point_cloud_topic_;
88  double scale_;
89  double padding_;
90  double max_range_;
91  unsigned int point_subsample_;
92  double max_update_rate_;
93  std::string filtered_cloud_topic_;
94  std::string ns_;
95  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
96 
97  message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
98  tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
99 
100  /* used to store all cells in the map which a given ray passes through during raycasting.
101  we cache this here because it dynamically pre-allocates a lot of memory in its contsructor */
102  octomap::KeyRay key_ray_;
103 
104  std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
105  std::vector<int> mask_;
106 };
107 } // namespace occupancy_map_monitor
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...
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(...
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape) override
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89