Skip to content

Commit 74876a6

Browse files
Address PR comments
1 parent ca47b2e commit 74876a6

24 files changed

+407
-505
lines changed

fuse_optimizers/CMakeLists.txt

+6-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11
cmake_minimum_required(VERSION 3.0.2)
22
project(fuse_optimizers)
33

4-
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fopenmp")
5-
64
set(build_depends
75
diagnostic_updater
86
fuse_constraints
@@ -14,6 +12,8 @@ set(build_depends
1412
std_srvs
1513
)
1614

15+
find_package(OpenMP)
16+
1717
find_package(catkin REQUIRED COMPONENTS
1818
${build_depends}
1919
)
@@ -51,12 +51,16 @@ target_include_directories(${PROJECT_NAME}
5151
)
5252
target_link_libraries(${PROJECT_NAME}
5353
${catkin_LIBRARIES}
54+
${OpenMP_CXX_LIBRARIES}
5455
)
5556
set_target_properties(${PROJECT_NAME}
5657
PROPERTIES
5758
CXX_STANDARD 14
5859
CXX_STANDARD_REQUIRED YES
5960
)
61+
target_compile_options(${PROJECT_NAME}
62+
PRIVATE ${OpenMP_CXX_FLAGS}
63+
)
6064

6165
## batch_optimizer node
6266
add_executable(batch_optimizer_node

fuse_optimizers/include/fuse_optimizers/batch_optimizer.h

+13-20
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,8 @@
5151
#include <utility>
5252
#include <vector>
5353

54-
5554
namespace fuse_optimizers
5655
{
57-
5856
/**
5957
* @brief A simple optimizer implementation that uses batch optimization
6058
*
@@ -107,10 +105,8 @@ class BatchOptimizer : public Optimizer
107105
* @param[in] node_handle A node handle in the global namespace
108106
* @param[in] private_node_handle A node handle in the node's private namespace
109107
*/
110-
BatchOptimizer(
111-
fuse_core::Graph::UniquePtr graph,
112-
const ros::NodeHandle& node_handle = ros::NodeHandle(),
113-
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
108+
BatchOptimizer(fuse_core::Graph::UniquePtr graph, const ros::NodeHandle& node_handle = ros::NodeHandle(),
109+
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
114110

115111
/**
116112
* @brief Destructor
@@ -126,11 +122,10 @@ class BatchOptimizer : public Optimizer
126122
std::string sensor_name;
127123
fuse_core::Transaction::SharedPtr transaction;
128124

129-
TransactionQueueElement(
130-
const std::string& sensor_name,
131-
fuse_core::Transaction::SharedPtr transaction) :
132-
sensor_name(sensor_name),
133-
transaction(std::move(transaction)) {}
125+
TransactionQueueElement(const std::string& sensor_name, fuse_core::Transaction::SharedPtr transaction)
126+
: sensor_name(sensor_name), transaction(std::move(transaction))
127+
{
128+
}
134129
};
135130

136131
/**
@@ -145,19 +140,19 @@ class BatchOptimizer : public Optimizer
145140
fuse_core::Transaction::SharedPtr combined_transaction_; //!< Transaction used aggregate constraints and variables
146141
//!< from multiple sensors and motions models before being
147142
//!< applied to the graph.
148-
std::mutex combined_transaction_mutex_; //!< Synchronize access to the combined transaction across different threads
149-
ParameterType params_; //!< Configuration settings for this optimizer
143+
std::mutex combined_transaction_mutex_; //!< Synchronize access to the combined transaction across different threads
144+
ParameterType params_; //!< Configuration settings for this optimizer
150145
std::atomic<bool> optimization_request_; //!< Flag to trigger a new optimization
151146
std::condition_variable optimization_requested_; //!< Condition variable used by the optimization thread to wait
152147
//!< until a new optimization is requested by the main thread
153-
std::mutex optimization_requested_mutex_; //!< Required condition variable mutex
154-
std::thread optimization_thread_; //!< Thread used to run the optimizer as a background process
155-
ros::Timer optimize_timer_; //!< Trigger an optimization operation at a fixed frequency
148+
std::mutex optimization_requested_mutex_; //!< Required condition variable mutex
149+
std::thread optimization_thread_; //!< Thread used to run the optimizer as a background process
150+
ros::Timer optimize_timer_; //!< Trigger an optimization operation at a fixed frequency
156151
TransactionQueue pending_transactions_; //!< The set of received transactions that have not been added to the
157152
//!< optimizer yet. Transactions are added by the main thread, and removed
158153
//!< and processed by the optimization thread.
159154
std::mutex pending_transactions_mutex_; //!< Synchronize modification of the pending_transactions_ container
160-
ros::Time start_time_; //!< The timestamp of the first ignition sensor transaction
155+
ros::Time start_time_; //!< The timestamp of the first ignition sensor transaction
161156
bool started_; //!< Flag indicating the optimizer is ready/has received a transaction from an ignition sensor
162157

163158
/**
@@ -200,9 +195,7 @@ class BatchOptimizer : public Optimizer
200195
* to generate connected constraints.
201196
* @param[in] transaction The populated Transaction object created by the loaded SensorModel plugin
202197
*/
203-
void transactionCallback(
204-
const std::string& sensor_name,
205-
fuse_core::Transaction::SharedPtr transaction) override;
198+
void transactionCallback(const std::string& sensor_name, fuse_core::Transaction::SharedPtr transaction) override;
206199

207200
/**
208201
* @brief Update and publish diagnotics

fuse_optimizers/include/fuse_optimizers/batch_optimizer_params.h

+2-4
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
*/
@@ -62,15 +60,15 @@ struct BatchOptimizerParams
6260
* may be specified in either the "optimization_period" parameter in seconds, or in the "optimization_frequency"
6361
* parameter in Hz.
6462
*/
65-
ros::Duration optimization_period { 0.1 };
63+
ros::Duration optimization_period{ 0.1 };
6664

6765
/**
6866
* @brief The maximum time to wait for motion models to be generated for a received transaction.
6967
*
7068
* Transactions are processed sequentially, so no new transactions will be added to the graph while waiting for
7169
* motion models to be generated. Once the timeout expires, that transaction will be deleted from the queue.
7270
*/
73-
ros::Duration transaction_timeout { 0.1 };
71+
ros::Duration transaction_timeout{ 0.1 };
7472

7573
/**
7674
* @brief Ceres Solver::Options object that controls various aspects of the optimizer.

fuse_optimizers/include/fuse_optimizers/fixed_lag_smoother.h

+7-11
Original file line numberDiff line numberDiff line change
@@ -113,11 +113,9 @@ class FixedLagSmoother : public WindowedOptimizer
113113
* @param[in] node_handle A node handle in the global namespace
114114
* @param[in] private_node_handle A node handle in the node's private namespace
115115
*/
116-
FixedLagSmoother(
117-
fuse_core::Graph::UniquePtr graph,
118-
const ParameterType::SharedPtr& params,
119-
const ros::NodeHandle& node_handle = ros::NodeHandle(),
120-
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
116+
FixedLagSmoother(fuse_core::Graph::UniquePtr graph, const ParameterType::SharedPtr& params,
117+
const ros::NodeHandle& node_handle = ros::NodeHandle(),
118+
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
121119

122120
/**
123121
* @brief Constructor
@@ -129,18 +127,16 @@ class FixedLagSmoother : public WindowedOptimizer
129127
* @param[in] node_handle A node handle in the global namespace
130128
* @param[in] private_node_handle A node handle in the node's private namespace
131129
*/
132-
explicit FixedLagSmoother(
133-
fuse_core::Graph::UniquePtr graph,
134-
const ros::NodeHandle& node_handle = ros::NodeHandle(),
135-
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
130+
explicit FixedLagSmoother(fuse_core::Graph::UniquePtr graph, const ros::NodeHandle& node_handle = ros::NodeHandle(),
131+
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
136132

137133
protected:
138134
// Read-only after construction
139135
ParameterType::SharedPtr params_; //!< Configuration settings for this fixed-lag smoother
140136

141137
// Guarded by mutex_
142-
std::mutex mutex_; //!< Mutex held while the fixed-lag smoother variables are modified
143-
ros::Time lag_expiration_; //!< The oldest stamp that is inside the fixed-lag smoother window
138+
std::mutex mutex_; //!< Mutex held while the fixed-lag smoother variables are modified
139+
ros::Time lag_expiration_; //!< The oldest stamp that is inside the fixed-lag smoother window
144140
VariableStampIndex timestamp_tracking_; //!< Object that tracks the timestamp associated with each variable
145141

146142
/**

fuse_optimizers/include/fuse_optimizers/fixed_lag_smoother_params.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ struct FixedLagSmootherParams : public WindowedOptimizerParams
5959
/**
6060
* @brief The duration of the smoothing window in seconds
6161
*/
62-
ros::Duration lag_duration { 5.0 };
62+
ros::Duration lag_duration{ 5.0 };
6363

6464
/**
6565
* @brief Method for loading parameter values from ROS.

fuse_optimizers/include/fuse_optimizers/fixed_size_smoother.h

+11-15
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
/*
22
* Software License Agreement (BSD License)
33
*
4-
* Copyright (c) 2019, Locus Robotics
4+
* Copyright (c) 2022, Locus Robotics
55
* All rights reserved.
66
*
77
* Redistribution and use in source and binary forms, with or without
@@ -50,17 +50,17 @@
5050
namespace fuse_optimizers
5151
{
5252
/**
53-
* @brief A fixed-Size smoother implementation that marginalizes out variables that are older than a defined Size time
53+
* @brief A fixed-2ize smoother implementation that marginalizes out variables that are older than a defined buffer size
5454
*
5555
* This implementation assumes that all added variable types are either derived from the fuse_variables::Stamped class,
5656
* or are directly connected to at least one fuse_variables::Stamped variable via a constraint. The current time of
57-
* the fixed-Size smoother is determined by the newest stamp of all added fuse_variables::Stamped variables.
57+
* the fixed-size smoother is determined by the newest stamp of all added fuse_variables::Stamped variables.
5858
*
5959
* During optimization:
6060
* (1) new variables and constraints are added to the graph
6161
* (2) the augmented graph is optimized and the variable values are updated
6262
* (3) all motion models, sensors, and publishers are notified of the updated graph
63-
* (4) all variables older than "current time - Size duration" are marginalized out.
63+
* (4) all variables outside of the fixed buffer are marginalized out
6464
*
6565
* Optimization is performed at a fixed frequency, controlled by the \p optimization_frequency parameter. Received
6666
* sensor transactions are queued while the optimization is processing, then applied to the graph at the start of the
@@ -69,7 +69,7 @@ namespace fuse_optimizers
6969
* completion, and the next optimization will not begin until the next scheduled optimization period.
7070
*
7171
* Parameters:
72-
* - Size_duration (float, default: 5.0) The duration of the smoothing window in seconds
72+
* - num_states (float, default: 10) The number of unique timestamped states in the window
7373
* - motion_models (struct array) The set of motion model plugins to load
7474
* @code{.yaml}
7575
* - name: string (A unique name for this motion model)
@@ -113,11 +113,9 @@ class FixedSizeSmoother : public WindowedOptimizer
113113
* @param[in] node_handle A node handle in the global namespace
114114
* @param[in] private_node_handle A node handle in the node's private namespace
115115
*/
116-
FixedSizeSmoother(
117-
fuse_core::Graph::UniquePtr graph,
118-
const ParameterType::SharedPtr& params,
119-
const ros::NodeHandle& node_handle = ros::NodeHandle(),
120-
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
116+
FixedSizeSmoother(fuse_core::Graph::UniquePtr graph, const ParameterType::SharedPtr& params,
117+
const ros::NodeHandle& node_handle = ros::NodeHandle(),
118+
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
121119

122120
/**
123121
* @brief Constructor
@@ -129,17 +127,15 @@ class FixedSizeSmoother : public WindowedOptimizer
129127
* @param[in] node_handle A node handle in the global namespace
130128
* @param[in] private_node_handle A node handle in the node's private namespace
131129
*/
132-
explicit FixedSizeSmoother(
133-
fuse_core::Graph::UniquePtr graph,
134-
const ros::NodeHandle& node_handle = ros::NodeHandle(),
135-
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
130+
explicit FixedSizeSmoother(fuse_core::Graph::UniquePtr graph, const ros::NodeHandle& node_handle = ros::NodeHandle(),
131+
const ros::NodeHandle& private_node_handle = ros::NodeHandle("~"));
136132

137133
protected:
138134
// Read-only after construction
139135
ParameterType::SharedPtr params_; //!< Configuration settings for this fixed-Size smoother
140136

141137
// Guarded by mutex_
142-
std::mutex mutex_; //!< Mutex held while the fixed-size smoother variables are modified
138+
std::mutex mutex_; //!< Mutex held while the fixed-size smoother variables are modified
143139
VariableStampIndex timestamp_tracking_; //!< Object that tracks the timestamp associated with each variable
144140

145141
/**

fuse_optimizers/include/fuse_optimizers/fixed_size_smoother_params.h

+3-11
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
/*
22
* Software License Agreement (BSD License)
33
*
4-
* Copyright (c) 2019, Locus Robotics
4+
* Copyright (c) 2022, Locus Robotics
55
* All rights reserved.
66
*
77
* Redistribution and use in source and binary forms, with or without
@@ -34,18 +34,10 @@
3434
#ifndef FUSE_OPTIMIZERS_FIXED_SIZE_SMOOTHER_PARAMS_H
3535
#define FUSE_OPTIMIZERS_FIXED_SIZE_SMOOTHER_PARAMS_H
3636

37-
#include <fuse_core/ceres_options.h>
3837
#include <fuse_core/parameter.h>
3938
#include <fuse_optimizers/windowed_optimizer_params.h>
40-
#include <ros/duration.h>
4139
#include <ros/node_handle.h>
4240

43-
#include <ceres/solver.h>
44-
45-
#include <algorithm>
46-
#include <string>
47-
#include <vector>
48-
4941
namespace fuse_optimizers
5042
{
5143
/**
@@ -57,9 +49,9 @@ struct FixedSizeSmootherParams : public WindowedOptimizerParams
5749
SMART_PTR_DEFINITIONS(FixedSizeSmootherParams);
5850

5951
/**
60-
* @brief The duration of the smoothing window in seconds
52+
* @brief Thenumber of unique stamps in the window
6153
*/
62-
int num_states {10};
54+
int num_states{ 10 };
6355

6456
/**
6557
* @brief Method for loading parameter values from ROS.

0 commit comments

Comments
 (0)