moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
pointcloud_octomap_updater.hpp
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 <rclcpp/version.h>
42// For Rolling, Kilted, and newer
43#if RCLCPP_VERSION_GTE(29, 6, 0)
44#include <tf2_ros/message_filter.hpp>
45#include <tf2_ros/transform_listener.hpp>
46// For Jazzy and older
47#else
48#include <tf2_ros/message_filter.h>
49#include <tf2_ros/transform_listener.h>
50#endif
51#if RCLCPP_VERSION_GTE(28, 3, 3) // Rolling
52#include <message_filters/subscriber.hpp>
53#else
54#include <message_filters/subscriber.h>
55#endif
56#include <sensor_msgs/msg/point_cloud2.hpp>
59
60#include <memory>
61
63{
65{
66public:
69
70 bool setParams(const std::string& name_space) override;
71
72 bool initialize(const rclcpp::Node::SharedPtr& node) override;
73 void start() override;
74 void stop() override;
75 ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) override;
76 void forgetShape(ShapeHandle handle) override;
77
78protected:
79 virtual void updateMask(const sensor_msgs::msg::PointCloud2& cloud, const Eigen::Vector3d& sensor_origin,
80 std::vector<int>& mask);
81
82private:
83 bool getShapeTransform(ShapeHandle h, Eigen::Isometry3d& transform) const;
84 void cloudMsgCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg);
85
86 // TODO: Enable private node for publishing filtered point cloud
87 // ros::NodeHandle root_nh_;
88 // ros::NodeHandle private_nh_;
89 rclcpp::Node::SharedPtr node_;
90
91 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
92 std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
93
94 // Initialize clock type to RCL_ROS_TIME to prevent exception about time sources mismatch
95 rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
96
97 /* params */
98 std::string point_cloud_topic_;
99 double scale_;
100 double padding_;
101 double max_range_;
102 unsigned int point_subsample_;
103 double max_update_rate_;
104 std::string filtered_cloud_topic_;
105 std::string ns_;
106 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr filtered_cloud_publisher_;
107
108 message_filters::Subscriber<sensor_msgs::msg::PointCloud2>* point_cloud_subscriber_;
109 tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>* point_cloud_filter_;
110
111 /* used to store all cells in the map which a given ray passes through during raycasting.
112 we cache this here because it dynamically pre-allocates a lot of memory in its constructor */
113 octomap::KeyRay key_ray_;
114
115 std::unique_ptr<point_containment_filter::ShapeMask> shape_mask_;
116 std::vector<int> mask_;
117
118 rclcpp::Logger logger_;
119};
120} // 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