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