@@ -66,6 +66,12 @@ BatchOptimizer::BatchOptimizer(
6666
6767 // Start the optimization thread
6868 optimization_thread_ = std::thread (&BatchOptimizer::optimizationLoop, this );
69+
70+ // Advertise a service that resets the optimizer to its initial state
71+ reset_service_server_ = node_handle_.advertiseService (
72+ ros::names::resolve (params_.reset_service ),
73+ &BatchOptimizer::resetServiceCallback,
74+ this );
6975}
7076
7177BatchOptimizer::~BatchOptimizer ()
@@ -137,23 +143,26 @@ void BatchOptimizer::optimizationLoop()
137143 {
138144 break ;
139145 }
140- // Copy the combined transaction so it can be shared with all the plugins
141- fuse_core::Transaction::ConstSharedPtr const_transaction;
142146 {
143- std::lock_guard<std::mutex> lock (combined_transaction_mutex_);
144- const_transaction = std::move (combined_transaction_);
145- combined_transaction_ = fuse_core::Transaction::make_shared ();
147+ std::lock_guard<std::mutex> lock (optimization_mutex_);
148+ // Copy the combined transaction so it can be shared with all the plugins
149+ fuse_core::Transaction::ConstSharedPtr const_transaction;
150+ {
151+ std::lock_guard<std::mutex> lock (combined_transaction_mutex_);
152+ const_transaction = std::move (combined_transaction_);
153+ combined_transaction_ = fuse_core::Transaction::make_shared ();
154+ }
155+ // Update the graph
156+ graph_->update (*const_transaction);
157+ // Optimize the entire graph
158+ graph_->optimize (params_.solver_options );
159+ // Make a copy of the graph to share
160+ fuse_core::Graph::ConstSharedPtr const_graph = graph_->clone ();
161+ // Optimization is complete. Notify all the things about the graph changes.
162+ notify (const_transaction, const_graph);
163+ // Clear the request flag now that this optimization cycle is complete
164+ optimization_request_ = false ;
146165 }
147- // Update the graph
148- graph_->update (*const_transaction);
149- // Optimize the entire graph
150- graph_->optimize (params_.solver_options );
151- // Make a copy of the graph to share
152- fuse_core::Graph::ConstSharedPtr const_graph = graph_->clone ();
153- // Optimization is complete. Notify all the things about the graph changes.
154- notify (const_transaction, const_graph);
155- // Clear the request flag now that this optimization cycle is complete
156- optimization_request_ = false ;
157166 }
158167}
159168
@@ -238,4 +247,43 @@ void BatchOptimizer::setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper&
238247 }
239248}
240249
250+ bool BatchOptimizer::resetServiceCallback (std_srvs::Empty::Request&, std_srvs::Empty::Response&)
251+ {
252+ // Tell all the plugins to stop
253+ stopPlugins ();
254+ // Reset the optimizer state
255+ {
256+ std::lock_guard<std::mutex> lock (optimization_requested_mutex_);
257+ optimization_request_ = false ;
258+ }
259+ started_ = false ;
260+ // DANGER: The optimizationLoop() function obtains the lock optimization_mutex_ lock and the
261+ // combined_transaction_mutex_ lock at the same time. We perform a parallel locking scheme here to
262+ // prevent the possibility of deadlocks.
263+ {
264+ std::lock_guard<std::mutex> lock (optimization_mutex_);
265+ // Clear the combined transation
266+ {
267+ std::lock_guard<std::mutex> lock (combined_transaction_mutex_);
268+ combined_transaction_ = fuse_core::Transaction::make_shared ();
269+ }
270+ // Clear the graph and marginal tracking states
271+ graph_->clear ();
272+ }
273+ // Clear all pending transactions
274+ // The transaction callback and the optimization timer callback are the only other locations where
275+ // the pending_transactions_ variable is modified. As long as the BatchOptimizer node handle is
276+ // single-threaded, then pending_transactions_ variable cannot be modified while the reset callback
277+ // is running. Therefore, there are no timing or sequence issues with exactly where inside the reset
278+ // service callback the pending_transactions_ are cleared.
279+ {
280+ std::lock_guard<std::mutex> lock (pending_transactions_mutex_);
281+ pending_transactions_.clear ();
282+ }
283+ // Tell all the plugins to start
284+ startPlugins ();
285+
286+ return true ;
287+ }
288+
241289} // namespace fuse_optimizers
0 commit comments