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