moveit2
The MoveIt Motion Planning Framework for ROS 2.
pointcloud_octomap_updater.cpp
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 #include <cmath>
40 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
41 #include <tf2/LinearMath/Vector3.h>
42 #include <tf2/LinearMath/Transform.h>
43 #include <sensor_msgs/point_cloud2_iterator.hpp>
44 #include <tf2_ros/create_timer_interface.h>
45 #include <tf2_ros/create_timer_ros.h>
46 
47 #include <memory>
48 
49 namespace occupancy_map_monitor
50 {
51 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.pointcloud_octomap_updater");
53  : OccupancyMapUpdater("PointCloudUpdater")
54  , scale_(1.0)
55  , padding_(0.0)
56  , max_range_(std::numeric_limits<double>::infinity())
57  , point_subsample_(1)
58  , max_update_rate_(0)
59  , point_cloud_subscriber_(nullptr)
60  , point_cloud_filter_(nullptr)
61 {
62 }
63 
65 {
66  stopHelper();
67 }
68 
69 bool PointCloudOctomapUpdater::setParams(const std::string& name_space)
70 {
71  // This parameter is optional
72  node_->get_parameter_or(name_space + ".ns", ns_, std::string());
73  return node_->get_parameter(name_space + ".point_cloud_topic", point_cloud_topic_) &&
74  node_->get_parameter(name_space + ".max_range", max_range_) &&
75  node_->get_parameter(name_space + ".padding_offset", padding_) &&
76  node_->get_parameter(name_space + ".padding_scale", scale_) &&
77  node_->get_parameter(name_space + ".point_subsample", point_subsample_) &&
78  node_->get_parameter(name_space + ".max_update_rate", max_update_rate_) &&
79  node_->get_parameter(name_space + ".filtered_cloud_topic", filtered_cloud_topic_);
80 }
81 
82 bool PointCloudOctomapUpdater::initialize(const rclcpp::Node::SharedPtr& node)
83 {
84  node_ = node;
85  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
86  auto create_timer_interface =
87  std::make_shared<tf2_ros::CreateTimerROS>(node->get_node_base_interface(), node->get_node_timers_interface());
88  tf_buffer_->setCreateTimerInterface(create_timer_interface);
89  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
90  shape_mask_ = std::make_unique<point_containment_filter::ShapeMask>();
91  shape_mask_->setTransformCallback(
92  [this](ShapeHandle shape, Eigen::Isometry3d& tf) { return getShapeTransform(shape, tf); });
93 
94  return true;
95 }
96 
98 {
99  std::string prefix = "";
100  if (!ns_.empty())
101  prefix = ns_ + "/";
102 
103  if (!filtered_cloud_topic_.empty())
104  filtered_cloud_publisher_ =
105  node_->create_publisher<sensor_msgs::msg::PointCloud2>(prefix + filtered_cloud_topic_, 10);
106 
107  if (point_cloud_subscriber_)
108  return;
109  /* subscribe to point cloud topic using tf filter*/
110  point_cloud_subscriber_ = new message_filters::Subscriber<sensor_msgs::msg::PointCloud2>(node_, point_cloud_topic_);
111  if (tf_listener_ && tf_buffer_ && !monitor_->getMapFrame().empty())
112  {
113  point_cloud_filter_ = new tf2_ros::MessageFilter<sensor_msgs::msg::PointCloud2>(
114  *point_cloud_subscriber_, *tf_buffer_, monitor_->getMapFrame(), 5, node_);
115  point_cloud_filter_->registerCallback(
116  [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
117  RCLCPP_INFO(LOGGER, "Listening to '%s' using message filter with target frame '%s'", point_cloud_topic_.c_str(),
118  point_cloud_filter_->getTargetFramesString().c_str());
119  }
120  else
121  {
122  point_cloud_subscriber_->registerCallback(
123  [this](const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud) { cloudMsgCallback(cloud); });
124  RCLCPP_INFO(LOGGER, "Listening to '%s'", point_cloud_topic_.c_str());
125  }
126 }
127 
128 void PointCloudOctomapUpdater::stopHelper()
129 {
130  delete point_cloud_filter_;
131  delete point_cloud_subscriber_;
132 }
133 
135 {
136  stopHelper();
137  point_cloud_filter_ = nullptr;
138  point_cloud_subscriber_ = nullptr;
139 }
140 
141 ShapeHandle PointCloudOctomapUpdater::excludeShape(const shapes::ShapeConstPtr& shape)
142 {
143  ShapeHandle h = 0;
144  if (shape_mask_)
145  h = shape_mask_->addShape(shape, scale_, padding_);
146  else
147  RCLCPP_ERROR(LOGGER, "Shape filter not yet initialized!");
148  return h;
149 }
150 
152 {
153  if (shape_mask_)
154  shape_mask_->removeShape(handle);
155 }
156 
157 bool PointCloudOctomapUpdater::getShapeTransform(ShapeHandle h, Eigen::Isometry3d& transform) const
158 {
159  ShapeTransformCache::const_iterator it = transform_cache_.find(h);
160  if (it != transform_cache_.end())
161  {
162  transform = it->second;
163  }
164  return it != transform_cache_.end();
165 }
166 
167 void PointCloudOctomapUpdater::updateMask(const sensor_msgs::msg::PointCloud2& /*cloud*/,
168  const Eigen::Vector3d& /*sensor_origin*/, std::vector<int>& /*mask*/)
169 {
170 }
171 
172 void PointCloudOctomapUpdater::cloudMsgCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& cloud_msg)
173 {
174  RCLCPP_DEBUG(LOGGER, "Received a new point cloud message");
175  rclcpp::Time start = rclcpp::Clock(RCL_ROS_TIME).now();
176 
177  if (max_update_rate_ > 0)
178  {
179  // ensure we are not updating the octomap representation too often
180  if ((node_->now() - last_update_time_) <= rclcpp::Duration::from_seconds(1.0 / max_update_rate_))
181  return;
182  last_update_time_ = node_->now();
183  }
184 
185  if (monitor_->getMapFrame().empty())
186  monitor_->setMapFrame(cloud_msg->header.frame_id);
187 
188  /* get transform for cloud into map frame */
189  tf2::Stamped<tf2::Transform> map_h_sensor;
190  if (monitor_->getMapFrame() == cloud_msg->header.frame_id)
191  map_h_sensor.setIdentity();
192  else
193  {
194  if (tf_buffer_)
195  {
196  try
197  {
198  tf2::fromMsg(tf_buffer_->lookupTransform(monitor_->getMapFrame(), cloud_msg->header.frame_id,
199  cloud_msg->header.stamp),
200  map_h_sensor);
201  }
202  catch (tf2::TransformException& ex)
203  {
204  RCLCPP_ERROR_STREAM(LOGGER, "Transform error of sensor data: " << ex.what() << "; quitting callback");
205  return;
206  }
207  }
208  else
209  return;
210  }
211 
212  /* compute sensor origin in map frame */
213  const tf2::Vector3& sensor_origin_tf = map_h_sensor.getOrigin();
214  octomap::point3d sensor_origin(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
215  Eigen::Vector3d sensor_origin_eigen(sensor_origin_tf.getX(), sensor_origin_tf.getY(), sensor_origin_tf.getZ());
216 
217  if (!updateTransformCache(cloud_msg->header.frame_id, cloud_msg->header.stamp))
218  return;
219 
220  /* mask out points on the robot */
221  shape_mask_->maskContainment(*cloud_msg, sensor_origin_eigen, 0.0, max_range_, mask_);
222  updateMask(*cloud_msg, sensor_origin_eigen, mask_);
223 
224  octomap::KeySet free_cells, occupied_cells, model_cells, clip_cells;
225  std::unique_ptr<sensor_msgs::msg::PointCloud2> filtered_cloud;
226 
227  // We only use these iterators if we are creating a filtered_cloud for
228  // publishing. We cannot default construct these, so we use unique_ptr's
229  // to defer construction
230  std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_x;
231  std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_y;
232  std::unique_ptr<sensor_msgs::PointCloud2Iterator<float>> iter_filtered_z;
233 
234  if (!filtered_cloud_topic_.empty())
235  {
236  filtered_cloud = std::make_unique<sensor_msgs::msg::PointCloud2>();
237  filtered_cloud->header = cloud_msg->header;
238  sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
239  pcd_modifier.setPointCloud2FieldsByString(1, "xyz");
240  pcd_modifier.resize(cloud_msg->width * cloud_msg->height);
241 
242  // we have created a filtered_out, so we can create the iterators now
243  iter_filtered_x = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, "x");
244  iter_filtered_y = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, "y");
245  iter_filtered_z = std::make_unique<sensor_msgs::PointCloud2Iterator<float>>(*filtered_cloud, "z");
246  }
247  size_t filtered_cloud_size = 0;
248 
249  tree_->lockRead();
250 
251  try
252  {
253  /* do ray tracing to find which cells this point cloud indicates should be free, and which it indicates
254  * should be occupied */
255  for (unsigned int row = 0; row < cloud_msg->height; row += point_subsample_)
256  {
257  unsigned int row_c = row * cloud_msg->width;
258  sensor_msgs::PointCloud2ConstIterator<float> pt_iter(*cloud_msg, "x");
259  // set iterator to point at start of the current row
260  pt_iter += row_c;
261 
262  for (unsigned int col = 0; col < cloud_msg->width; col += point_subsample_, pt_iter += point_subsample_)
263  {
264  // if (mask_[row_c + col] == point_containment_filter::ShapeMask::CLIP)
265  // continue;
266 
267  /* check for NaN */
268  if (!std::isnan(pt_iter[0]) && !std::isnan(pt_iter[1]) && !std::isnan(pt_iter[2]))
269  {
270  /* occupied cell at ray endpoint if ray is shorter than max range and this point
271  isn't on a part of the robot*/
272  if (mask_[row_c + col] == point_containment_filter::ShapeMask::INSIDE)
273  {
274  // transform to map frame
275  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
276  model_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
277  }
278  else if (mask_[row_c + col] == point_containment_filter::ShapeMask::CLIP)
279  {
280  tf2::Vector3 clipped_point_tf =
281  map_h_sensor * (tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]).normalize() * max_range_);
282  clip_cells.insert(
283  tree_->coordToKey(clipped_point_tf.getX(), clipped_point_tf.getY(), clipped_point_tf.getZ()));
284  }
285  else
286  {
287  tf2::Vector3 point_tf = map_h_sensor * tf2::Vector3(pt_iter[0], pt_iter[1], pt_iter[2]);
288  occupied_cells.insert(tree_->coordToKey(point_tf.getX(), point_tf.getY(), point_tf.getZ()));
289  // build list of valid points if we want to publish them
290  if (filtered_cloud)
291  {
292  **iter_filtered_x = pt_iter[0];
293  **iter_filtered_y = pt_iter[1];
294  **iter_filtered_z = pt_iter[2];
295  ++filtered_cloud_size;
296  ++*iter_filtered_x;
297  ++*iter_filtered_y;
298  ++*iter_filtered_z;
299  }
300  }
301  }
302  }
303  }
304 
305  /* compute the free cells along each ray that ends at an occupied cell */
306  for (const octomap::OcTreeKey& occupied_cell : occupied_cells)
307  if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(occupied_cell), key_ray_))
308  free_cells.insert(key_ray_.begin(), key_ray_.end());
309 
310  /* compute the free cells along each ray that ends at a model cell */
311  for (const octomap::OcTreeKey& model_cell : model_cells)
312  if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(model_cell), key_ray_))
313  free_cells.insert(key_ray_.begin(), key_ray_.end());
314 
315  /* compute the free cells along each ray that ends at a clipped cell */
316  for (const octomap::OcTreeKey& clip_cell : clip_cells)
317  if (tree_->computeRayKeys(sensor_origin, tree_->keyToCoord(clip_cell), key_ray_))
318  free_cells.insert(key_ray_.begin(), key_ray_.end());
319  }
320  catch (...)
321  {
322  tree_->unlockRead();
323  return;
324  }
325 
326  tree_->unlockRead();
327 
328  /* cells that overlap with the model are not occupied */
329  for (const octomap::OcTreeKey& model_cell : model_cells)
330  occupied_cells.erase(model_cell);
331 
332  /* occupied cells are not free */
333  for (const octomap::OcTreeKey& occupied_cell : occupied_cells)
334  free_cells.erase(occupied_cell);
335 
336  tree_->lockWrite();
337 
338  try
339  {
340  /* mark free cells only if not seen occupied in this cloud */
341  for (const octomap::OcTreeKey& free_cell : free_cells)
342  tree_->updateNode(free_cell, false);
343 
344  /* now mark all occupied cells */
345  for (const octomap::OcTreeKey& occupied_cell : occupied_cells)
346  tree_->updateNode(occupied_cell, true);
347 
348  // set the logodds to the minimum for the cells that are part of the model
349  const float lg = tree_->getClampingThresMinLog() - tree_->getClampingThresMaxLog();
350  for (const octomap::OcTreeKey& model_cell : model_cells)
351  tree_->updateNode(model_cell, lg);
352  }
353  catch (...)
354  {
355  RCLCPP_ERROR(LOGGER, "Internal error while updating octree");
356  }
357  tree_->unlockWrite();
358  RCLCPP_DEBUG(LOGGER, "Processed point cloud in %lf ms", (node_->now() - start).seconds() * 1000.0);
359  tree_->triggerUpdateCallback();
360 
361  if (filtered_cloud)
362  {
363  sensor_msgs::PointCloud2Modifier pcd_modifier(*filtered_cloud);
364  pcd_modifier.resize(filtered_cloud_size);
365  filtered_cloud_publisher_->publish(*filtered_cloud);
366  }
367 }
368 } // namespace occupancy_map_monitor
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void setMapFrame(const std::string &frame)
Sets the map frame.
Base class for classes which update the occupancy map.
collision_detection::OccMapTreePtr tree_
bool updateTransformCache(const std::string &target_frame, const rclcpp::Time &target_time)
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
const rclcpp::Logger LOGGER
Definition: async_test.h:31