1
1
/*
2
2
* Software License Agreement (BSD License)
3
3
*
4
- * Copyright (c) 2019 , Locus Robotics
4
+ * Copyright (c) 2022 , Locus Robotics
5
5
* All rights reserved.
6
6
*
7
7
* Redistribution and use in source and binary forms, with or without
50
50
namespace fuse_optimizers
51
51
{
52
52
/* *
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
54
54
*
55
55
* This implementation assumes that all added variable types are either derived from the fuse_variables::Stamped class,
56
56
* 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.
58
58
*
59
59
* During optimization:
60
60
* (1) new variables and constraints are added to the graph
61
61
* (2) the augmented graph is optimized and the variable values are updated
62
62
* (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
64
64
*
65
65
* Optimization is performed at a fixed frequency, controlled by the \p optimization_frequency parameter. Received
66
66
* 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
69
69
* completion, and the next optimization will not begin until the next scheduled optimization period.
70
70
*
71
71
* 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
73
73
* - motion_models (struct array) The set of motion model plugins to load
74
74
* @code{.yaml}
75
75
* - name: string (A unique name for this motion model)
@@ -113,11 +113,9 @@ class FixedSizeSmoother : public WindowedOptimizer
113
113
* @param[in] node_handle A node handle in the global namespace
114
114
* @param[in] private_node_handle A node handle in the node's private namespace
115
115
*/
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(" ~" ));
121
119
122
120
/* *
123
121
* @brief Constructor
@@ -129,17 +127,15 @@ class FixedSizeSmoother : public WindowedOptimizer
129
127
* @param[in] node_handle A node handle in the global namespace
130
128
* @param[in] private_node_handle A node handle in the node's private namespace
131
129
*/
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(" ~" ));
136
132
137
133
protected:
138
134
// Read-only after construction
139
135
ParameterType::SharedPtr params_; // !< Configuration settings for this fixed-Size smoother
140
136
141
137
// 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
143
139
VariableStampIndex timestamp_tracking_; // !< Object that tracks the timestamp associated with each variable
144
140
145
141
/* *
0 commit comments