Skip to content

Commit 415971a

Browse files
Add a reset service to the batch optimizer, similar to the fixed-lag smoother (#360)
1 parent 2a7829c commit 415971a

File tree

3 files changed

+78
-17
lines changed

3 files changed

+78
-17
lines changed

fuse_optimizers/include/fuse_optimizers/batch_optimizer.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@
4040
#include <fuse_optimizers/batch_optimizer_params.h>
4141
#include <fuse_optimizers/optimizer.h>
4242
#include <ros/ros.h>
43+
#include <std_srvs/Empty.h>
4344

4445
#include <atomic>
4546
#include <condition_variable>
@@ -142,6 +143,7 @@ class BatchOptimizer : public Optimizer
142143
*/
143144
using TransactionQueue = std::multimap<ros::Time, TransactionQueueElement>;
144145

146+
std::mutex optimization_mutex_; //!< Mutex held while the graph is begin optimized
145147
fuse_core::Transaction::SharedPtr combined_transaction_; //!< Transaction used aggregate constraints and variables
146148
//!< from multiple sensors and motions models before being
147149
//!< applied to the graph.
@@ -159,6 +161,7 @@ class BatchOptimizer : public Optimizer
159161
std::mutex pending_transactions_mutex_; //!< Synchronize modification of the pending_transactions_ container
160162
ros::Time start_time_; //!< The timestamp of the first ignition sensor transaction
161163
bool started_; //!< Flag indicating the optimizer is ready/has received a transaction from an ignition sensor
164+
ros::ServiceServer reset_service_server_; //!< Service that resets the optimizer to its initial state
162165

163166
/**
164167
* @brief Generate motion model constraints for pending transactions
@@ -209,6 +212,11 @@ class BatchOptimizer : public Optimizer
209212
* @param[in] status The diagnostic status
210213
*/
211214
void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& status) override;
215+
216+
/**
217+
* @brief Service callback that resets the optimizer to its original state
218+
*/
219+
bool resetServiceCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
212220
};
213221

214222
} // namespace fuse_optimizers

fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.h

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,10 +45,8 @@
4545
#include <string>
4646
#include <vector>
4747

48-
4948
namespace fuse_optimizers
5049
{
51-
5250
/**
5351
* @brief Defines the set of parameters required by the fuse_optimizers::FixedLagSmoother class
5452
*/
@@ -64,6 +62,11 @@ struct BatchOptimizerParams
6462
*/
6563
ros::Duration optimization_period { 0.1 };
6664

65+
/**
66+
* @brief The topic name of the advertised reset service
67+
*/
68+
std::string reset_service { "~reset" };
69+
6770
/**
6871
* @brief The maximum time to wait for motion models to be generated for a received transaction.
6972
*
@@ -96,6 +99,8 @@ struct BatchOptimizerParams
9699
fuse_core::getPositiveParam(nh, "optimization_period", optimization_period);
97100
}
98101

102+
nh.getParam("reset_service", reset_service);
103+
99104
fuse_core::getPositiveParam(nh, "transaction_timeout", transaction_timeout);
100105

101106
fuse_core::loadSolverOptionsFromROS(ros::NodeHandle(nh, "solver_options"), solver_options);

fuse_optimizers/src/batch_optimizer.cpp

Lines changed: 63 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -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

7177
BatchOptimizer::~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

Comments
 (0)