38 #include <rclcpp/logging.hpp>
39 #include <rclcpp/clock.hpp>
43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.perception.lazy_free_space_updater");
48 , max_batch_size_(max_batch_size)
49 , max_sensor_delta_(1e-3)
50 , process_occupied_cells_set_(nullptr)
51 , process_model_cells_set_(nullptr)
52 , update_thread_([this] { lazyUpdateThread(); })
53 , process_thread_([
this] { processThread(); })
61 std::unique_lock<std::mutex> _(update_cell_sets_lock_);
62 update_condition_.notify_one();
65 std::unique_lock<std::mutex> _(cell_process_lock_);
66 process_condition_.notify_one();
68 update_thread_.join();
69 process_thread_.join();
73 const octomap::point3d& sensor_origin)
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();
84 void LazyFreeSpaceUpdater::pushBatchToProcess(OcTreeKeyCountMap* occupied_cells, octomap::KeySet* model_cells,
85 const octomap::point3d& sensor_origin)
90 if (cell_process_lock_.try_lock())
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();
100 RCLCPP_WARN(LOGGER,
"Previous batch update did not complete. Ignoring set of cells to be freed.");
101 delete occupied_cells;
106 void LazyFreeSpaceUpdater::processThread()
108 const float lg_0 = tree_->getClampingThresMinLog() - tree_->getClampingThresMaxLog();
109 const float lg_miss = tree_->getProbMissLog();
111 octomap::KeyRay key_ray1, key_ray2;
112 OcTreeKeyCountMap free_cells1, free_cells2;
119 std::unique_lock<std::mutex> ulock(cell_process_lock_);
120 while (!process_occupied_cells_set_ && running_)
121 process_condition_.wait(ulock);
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());
132 rclcpp::Time start = clock.now();
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;
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)
158 for (std::pair<const octomap::OcTreeKey, unsigned int>& it : *process_occupied_cells_set_)
160 free_cells1.erase(it.first);
161 free_cells2.erase(it.first);
164 for (
const octomap::OcTreeKey& it : *process_model_cells_set_)
166 free_cells1.erase(it);
167 free_cells2.erase(it);
169 RCLCPP_DEBUG(LOGGER,
"Marking %lu cells as free...", (
long unsigned int)(free_cells1.size() + free_cells2.size()));
176 for (
const octomap::OcTreeKey& it : *process_model_cells_set_)
177 tree_->updateNode(it, lg_0);
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);
187 RCLCPP_ERROR(LOGGER,
"Internal error while updating octree");
189 tree_->unlockWrite();
190 tree_->triggerUpdateCallback();
192 RCLCPP_DEBUG(LOGGER,
"Marked free cells in %lf ms", (clock.now() - start).seconds() * 1000.0);
194 delete process_occupied_cells_set_;
195 process_occupied_cells_set_ =
nullptr;
196 delete process_model_cells_set_;
197 process_model_cells_set_ =
nullptr;
201 void LazyFreeSpaceUpdater::lazyUpdateThread()
203 OcTreeKeyCountMap* occupied_cells_set =
nullptr;
204 octomap::KeySet* model_cells_set =
nullptr;
205 octomap::point3d sensor_origin;
206 unsigned int batch_size = 0;
210 std::unique_lock<std::mutex> ulock(update_cell_sets_lock_);
211 while (occupied_cells_sets_.empty() && running_)
212 update_condition_.wait(ulock);
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]++;
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();
232 while (!occupied_cells_sets_.empty())
234 if ((sensor_origins_.front() - sensor_origin).norm() > max_sensor_delta_)
236 RCLCPP_DEBUG(LOGGER,
"Pushing %u sets of occupied/model cells to free cells update thread (origin changed)",
238 pushBatchToProcess(occupied_cells_set, model_cells_set, sensor_origin);
242 sensor_origins_.pop_front();
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();
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();
256 if (batch_size >= max_batch_size_)
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;
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