moveit2
The MoveIt Motion Planning Framework for ROS 2.
depth_image_octomap_updater.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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: Ioan Sucan */
36 
37 #pragma once
38 
39 #include <rclcpp/rclcpp.hpp>
40 #include <tf2_ros/buffer.h>
45 #include <image_transport/image_transport.hpp>
46 #include <memory>
47 
48 namespace occupancy_map_monitor
49 {
51 {
52 public:
54  ~DepthImageOctomapUpdater() override;
55 
56  bool setParams(const std::string& name_space) override;
57  bool initialize(const rclcpp::Node::SharedPtr& node) override;
58  void start() override;
59  void stop() override;
60  ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape) override;
61  void forgetShape(ShapeHandle handle) override;
62 
63 private:
64  void depthImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& depth_msg,
65  const sensor_msgs::msg::CameraInfo::ConstSharedPtr& info_msg);
66  bool getShapeTransform(mesh_filter::MeshHandle h, Eigen::Isometry3d& transform) const;
67 
68  rclcpp::Node::SharedPtr node_;
69  std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
70  std::unique_ptr<image_transport::ImageTransport> input_depth_transport_;
71  std::unique_ptr<image_transport::ImageTransport> model_depth_transport_;
72  std::unique_ptr<image_transport::ImageTransport> filtered_depth_transport_;
73  std::unique_ptr<image_transport::ImageTransport> filtered_label_transport_;
74 
75  image_transport::CameraSubscriber sub_depth_image_;
76  image_transport::CameraPublisher pub_model_depth_image_;
77  image_transport::CameraPublisher pub_filtered_depth_image_;
78  image_transport::CameraPublisher pub_filtered_label_image_;
79 
80  // Initialize clock type to RCL_ROS_TIME to prevent exception about time sources mismatch
81  rclcpp::Time last_update_time_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
82 
83  std::string filtered_cloud_topic_;
84  std::string ns_;
85  std::string sensor_type_;
86  std::string image_topic_;
87  std::size_t queue_size_;
88  double near_clipping_plane_distance_;
89  double far_clipping_plane_distance_;
90  double shadow_threshold_;
91  double padding_scale_;
92  double padding_offset_;
93  double max_update_rate_;
94  unsigned int skip_vertical_pixels_;
95  unsigned int skip_horizontal_pixels_;
96 
97  unsigned int image_callback_count_;
98  double average_callback_dt_;
99  unsigned int good_tf_;
100  unsigned int failed_tf_;
101 
102  std::unique_ptr<mesh_filter::MeshFilter<mesh_filter::StereoCameraModel> > mesh_filter_;
103  std::unique_ptr<LazyFreeSpaceUpdater> free_space_updater_;
104 
105  std::vector<double> x_cache_, y_cache_;
106  double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_;
107  std::vector<unsigned int> filtered_labels_;
108  rclcpp::Time last_depth_callback_start_;
109  rclcpp::Logger logger_;
110 };
111 } // namespace occupancy_map_monitor
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
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...
Base class for classes which update the occupancy map.
unsigned int MeshHandle