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