moveit2
The MoveIt Motion Planning Framework for ROS 2.
lazy_free_space_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: Ioan Sucan */
36 
38 #include <rclcpp/logging.hpp>
39 #include <rclcpp/clock.hpp>
40 #include <moveit/utils/logger.hpp>
41 
42 namespace occupancy_map_monitor
43 {
44 
46  : tree_(tree)
47  , running_(true)
48  , max_batch_size_(max_batch_size)
49  , max_sensor_delta_(1e-3) // 1mm
50  , process_occupied_cells_set_(nullptr)
51  , process_model_cells_set_(nullptr)
52  , update_thread_([this] { lazyUpdateThread(); })
53  , process_thread_([this] { processThread(); })
54  , logger_(moveit::getLogger("moveit.ros.lazy_free_space_updater"))
55 {
56 }
57 
59 {
60  running_ = false;
61  {
62  std::unique_lock<std::mutex> _(update_cell_sets_lock_);
63  update_condition_.notify_one();
64  }
65  {
66  std::unique_lock<std::mutex> _(cell_process_lock_);
67  process_condition_.notify_one();
68  }
69  update_thread_.join();
70  process_thread_.join();
71 }
72 
73 void LazyFreeSpaceUpdater::pushLazyUpdate(octomap::KeySet* occupied_cells, octomap::KeySet* model_cells,
74  const octomap::point3d& sensor_origin)
75 {
76  RCLCPP_DEBUG(logger_, "Pushing %lu occupied cells and %lu model cells for lazy updating...",
77  static_cast<long unsigned int>(occupied_cells->size()),
78  static_cast<long unsigned int>(model_cells->size()));
79  std::scoped_lock _(update_cell_sets_lock_);
80  occupied_cells_sets_.push_back(occupied_cells);
81  model_cells_sets_.push_back(model_cells);
82  sensor_origins_.push_back(sensor_origin);
83  update_condition_.notify_one();
84 }
85 
86 void LazyFreeSpaceUpdater::pushBatchToProcess(OcTreeKeyCountMap* occupied_cells, octomap::KeySet* model_cells,
87  const octomap::point3d& sensor_origin)
88 {
89  // this is basically a queue of size 1. if this function is called repeatedly without any work being done by
90  // processThread(),
91  // data can be lost; this is intentional, to avoid spending too much time clearing the octomap
92  if (cell_process_lock_.try_lock())
93  {
94  process_occupied_cells_set_ = occupied_cells;
95  process_model_cells_set_ = model_cells;
96  process_sensor_origin_ = sensor_origin;
97  process_condition_.notify_one();
98  cell_process_lock_.unlock();
99  }
100  else
101  {
102  RCLCPP_WARN(logger_, "Previous batch update did not complete. Ignoring set of cells to be freed.");
103  delete occupied_cells;
104  delete model_cells;
105  }
106 }
107 
108 void LazyFreeSpaceUpdater::processThread()
109 {
110  const float lg_0 = tree_->getClampingThresMinLog() - tree_->getClampingThresMaxLog();
111  const float lg_miss = tree_->getProbMissLog();
112 
113  octomap::KeyRay key_ray1, key_ray2;
114  OcTreeKeyCountMap free_cells1, free_cells2;
115 
116  while (running_)
117  {
118  free_cells1.clear();
119  free_cells2.clear();
120 
121  std::unique_lock<std::mutex> ulock(cell_process_lock_);
122  while (!process_occupied_cells_set_ && running_)
123  process_condition_.wait(ulock);
124 
125  if (!running_)
126  break;
127 
128  RCLCPP_DEBUG(logger_,
129  "Begin processing batched update: marking free cells due to %lu occupied cells and %lu model cells",
130  static_cast<long unsigned int>(process_occupied_cells_set_->size()),
131  static_cast<long unsigned int>(process_model_cells_set_->size()));
132 
133  rclcpp::Clock clock;
134  rclcpp::Time start = clock.now();
135  tree_->lockRead();
136 
137 #pragma omp sections
138  {
139 #pragma omp section
140  {
141  /* compute the free cells along each ray that ends at an occupied cell */
142  for (std::pair<const octomap::OcTreeKey, unsigned int>& it : *process_occupied_cells_set_)
143  {
144  if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(it.first), key_ray1))
145  {
146  for (octomap::OcTreeKey& jt : key_ray1)
147  free_cells1[jt] += it.second;
148  }
149  }
150  }
151 
152 #pragma omp section
153  {
154  /* compute the free cells along each ray that ends at a model cell */
155  for (const octomap::OcTreeKey& it : *process_model_cells_set_)
156  {
157  if (tree_->computeRayKeys(process_sensor_origin_, tree_->keyToCoord(it), key_ray2))
158  {
159  for (octomap::OcTreeKey& jt : key_ray2)
160  free_cells2[jt]++;
161  }
162  }
163  }
164  }
165 
166  tree_->unlockRead();
167 
168  for (std::pair<const octomap::OcTreeKey, unsigned int>& it : *process_occupied_cells_set_)
169  {
170  free_cells1.erase(it.first);
171  free_cells2.erase(it.first);
172  }
173 
174  for (const octomap::OcTreeKey& it : *process_model_cells_set_)
175  {
176  free_cells1.erase(it);
177  free_cells2.erase(it);
178  }
179  RCLCPP_DEBUG(logger_, "Marking %lu cells as free...",
180  static_cast<long unsigned int>(free_cells1.size() + free_cells2.size()));
181 
182  tree_->lockWrite();
183 
184  try
185  {
186  // set the logodds to the minimum for the cells that are part of the model
187  for (const octomap::OcTreeKey& it : *process_model_cells_set_)
188  tree_->updateNode(it, lg_0);
189 
190  /* mark free cells only if not seen occupied in this cloud */
191  for (std::pair<const octomap::OcTreeKey, unsigned int>& it : free_cells1)
192  tree_->updateNode(it.first, it.second * lg_miss);
193  for (std::pair<const octomap::OcTreeKey, unsigned int>& it : free_cells2)
194  tree_->updateNode(it.first, it.second * lg_miss);
195  }
196  catch (...)
197  {
198  RCLCPP_ERROR(logger_, "Internal error while updating octree");
199  }
200  tree_->unlockWrite();
201  tree_->triggerUpdateCallback();
202 
203  RCLCPP_DEBUG(logger_, "Marked free cells in %lf ms", (clock.now() - start).seconds() * 1000.0);
204 
205  delete process_occupied_cells_set_;
206  process_occupied_cells_set_ = nullptr;
207  delete process_model_cells_set_;
208  process_model_cells_set_ = nullptr;
209  }
210 }
211 
212 void LazyFreeSpaceUpdater::lazyUpdateThread()
213 {
214  OcTreeKeyCountMap* occupied_cells_set = nullptr;
215  octomap::KeySet* model_cells_set = nullptr;
216  octomap::point3d sensor_origin;
217  unsigned int batch_size = 0;
218 
219  while (running_)
220  {
221  std::unique_lock<std::mutex> ulock(update_cell_sets_lock_);
222  while (occupied_cells_sets_.empty() && running_)
223  update_condition_.wait(ulock);
224 
225  if (!running_)
226  break;
227 
228  if (batch_size == 0)
229  {
230  occupied_cells_set = new OcTreeKeyCountMap();
231  octomap::KeySet* s = occupied_cells_sets_.front();
232  occupied_cells_sets_.pop_front();
233  for (const octomap::OcTreeKey& it : *s)
234  (*occupied_cells_set)[it]++;
235  delete s;
236  model_cells_set = model_cells_sets_.front();
237  model_cells_sets_.pop_front();
238  sensor_origin = sensor_origins_.front();
239  sensor_origins_.pop_front();
240  batch_size++;
241  }
242 
243  while (!occupied_cells_sets_.empty())
244  {
245  if ((sensor_origins_.front() - sensor_origin).norm() > max_sensor_delta_)
246  {
247  RCLCPP_DEBUG(logger_, "Pushing %u sets of occupied/model cells to free cells update thread (origin changed)",
248  batch_size);
249  pushBatchToProcess(occupied_cells_set, model_cells_set, sensor_origin);
250  batch_size = 0;
251  break;
252  }
253  sensor_origins_.pop_front();
254 
255  octomap::KeySet* add_occ = occupied_cells_sets_.front();
256  for (const octomap::OcTreeKey& it : *add_occ)
257  (*occupied_cells_set)[it]++;
258  occupied_cells_sets_.pop_front();
259  delete add_occ;
260  octomap::KeySet* mod_occ = model_cells_sets_.front();
261  model_cells_set->insert(mod_occ->begin(), mod_occ->end());
262  model_cells_sets_.pop_front();
263  delete mod_occ;
264  batch_size++;
265  }
266 
267  if (batch_size >= max_batch_size_)
268  {
269  RCLCPP_DEBUG(logger_, "Pushing %u sets of occupied/model cells to free cells update thread", batch_size);
270  pushBatchToProcess(occupied_cells_set, model_cells_set, sensor_origin);
271  occupied_cells_set = nullptr;
272  batch_size = 0;
273  }
274  }
275 }
276 } // namespace occupancy_map_monitor
void pushLazyUpdate(octomap::KeySet *occupied_cells, octomap::KeySet *model_cells, const octomap::point3d &sensor_origin)
LazyFreeSpaceUpdater(const collision_detection::OccMapTreePtr &tree, unsigned int max_batch_size=10)
std::shared_ptr< OccMapTree > OccMapTreePtr
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79