59 using namespace gtsam;
62 int main(
int argc,
char** argv) {
89 newValues.
insert(priorKey, priorMean);
90 newTimestamps[priorKey] = 0.0;
98 Key previousKey(1000 * (
time-deltaT));
102 newTimestamps[currentKey] =
time;
108 newValues.
insert(currentKey, currentPose);
111 Pose2 odometryMeasurement1 =
Pose2(0.61, -0.08, 0.02);
112 auto odometryNoise1 = noiseModel::Diagonal::Sigmas(
Vector3(0.1, 0.1, 0.05));
115 Pose2 odometryMeasurement2 =
Pose2(0.47, 0.03, 0.01);
116 auto odometryNoise2 = noiseModel::Diagonal::Sigmas(
Vector3(0.05, 0.05, 0.05));
122 if(
time >= lag+deltaT) {
123 oldKeys.push_back(1000 * (
time-lag-deltaT));
127 concurrentFilter.
update(newFactors, newValues, oldKeys);
128 fixedlagSmoother.
update(newFactors, newValues, newTimestamps);
129 batchSmoother.
update(newFactors, newValues, newTimestamps);
134 concurrentSmoother.
update();
139 cout << setprecision(5) <<
"Timestamp = " <<
time << endl;
146 newTimestamps.clear();
150 cout <<
"******************************************************************" << endl;
151 cout <<
"All three versions should be identical." << endl;
152 cout <<
"Adding a loop closure factor to the Batch version only." << endl;
153 cout <<
"******************************************************************" << endl;
158 Key loopKey1(1000 * (0.0));
159 Key loopKey2(1000 * (5.0));
160 Pose2 loopMeasurement =
Pose2(9.5, 1.00, 0.00);
161 auto loopNoise = noiseModel::Diagonal::Sigmas(
Vector3(0.5, 0.5, 0.25));
162 NonlinearFactor::shared_ptr loopFactor(
new BetweenFactor<Pose2>(loopKey1, loopKey2, loopMeasurement, loopNoise));
177 Key previousKey(1000 * (
time-deltaT));
181 newTimestamps[currentKey] =
time;
187 newValues.
insert(currentKey, currentPose);
190 Pose2 odometryMeasurement1 =
Pose2(0.61, -0.08, 0.02);
191 auto odometryNoise1 = noiseModel::Diagonal::Sigmas(
Vector3(0.1, 0.1, 0.05));
194 Pose2 odometryMeasurement2 =
Pose2(0.47, 0.03, 0.01);
195 auto odometryNoise2 = noiseModel::Diagonal::Sigmas(
Vector3(0.05, 0.05, 0.05));
201 if(
time >= lag+deltaT) {
202 oldKeys.push_back(1000 * (
time-lag-deltaT));
206 concurrentFilter.
update(newFactors, newValues, oldKeys);
207 fixedlagSmoother.
update(newFactors, newValues, newTimestamps);
208 batchSmoother.
update(newFactors, newValues, newTimestamps);
213 concurrentSmoother.
update();
218 cout << setprecision(5) <<
"Timestamp = " <<
time << endl;
225 newTimestamps.clear();
229 cout <<
"******************************************************************" << endl;
230 cout <<
"The Concurrent system and the Fixed-Lag Smoother should be " << endl;
231 cout <<
"the same, but the Batch version has a loop closure." << endl;
232 cout <<
"Adding the loop closure factor to the Concurrent version." << endl;
233 cout <<
"This will not update the Concurrent Filter until the next " << endl;
234 cout <<
"synchronization, but the Concurrent solution should be identical " << endl;
235 cout <<
"to the Batch solution afterwards." << endl;
236 cout <<
"******************************************************************" << endl;
250 Key previousKey(1000 * (
time-deltaT));
254 newTimestamps[currentKey] =
time;
260 newValues.
insert(currentKey, currentPose);
263 Pose2 odometryMeasurement1 =
Pose2(0.61, -0.08, 0.02);
264 auto odometryNoise1 = noiseModel::Diagonal::Sigmas(
Vector3(0.1, 0.1, 0.05));
267 Pose2 odometryMeasurement2 =
Pose2(0.47, 0.03, 0.01);
268 auto odometryNoise2 = noiseModel::Diagonal::Sigmas(
Vector3(0.05, 0.05, 0.05));
274 if(
time >= lag+deltaT) {
275 oldKeys.push_back(1000 * (
time-lag-deltaT));
279 concurrentFilter.
update(newFactors, newValues, oldKeys);
280 fixedlagSmoother.
update(newFactors, newValues, newTimestamps);
281 batchSmoother.
update(newFactors, newValues, newTimestamps);
286 concurrentSmoother.
update();
288 cout <<
"******************************************************************" << endl;
289 cout <<
"Syncing Concurrent Filter and Smoother." << endl;
290 cout <<
"******************************************************************" << endl;
295 cout << setprecision(5) <<
"Timestamp = " <<
time << endl;
302 newTimestamps.clear();
309 cout <<
"After 15.0 seconds, each version contains to the following keys:" << endl;
310 cout <<
" Concurrent Filter Keys: " << endl;
312 cout << setprecision(5) <<
" Key: " <<
key << endl;
314 cout <<
" Concurrent Smoother Keys: " << endl;
316 cout << setprecision(5) <<
" Key: " <<
key << endl;
318 cout <<
" Fixed-Lag Smoother Keys: " << endl;
319 for(
const auto& key_timestamp: fixedlagSmoother.
timestamps()) {
320 cout << setprecision(5) <<
" Key: " << key_timestamp.first << endl;
322 cout <<
" Batch Smoother Keys: " << endl;
323 for(
const auto& key_timestamp: batchSmoother.
timestamps()) {
324 cout << setprecision(5) <<
" Key: " << key_timestamp.first << endl;
const gtsam::Symbol key('X', 0)
Values calculateEstimate() const
Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const KeyTimestampMap ×tamps=KeyTimestampMap(), const FactorIndices &factorsToRemove=FactorIndices()) override
A Levenberg-Marquardt Batch Filter that implements the Concurrent Filtering and Smoothing interface...
std::map< Key, double > KeyTimestampMap
Typedef for a Key-Timestamp map/database.
int main(int argc, char **argv)
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const std::optional< FastList< Key > > &keysToMove={}, const std::optional< std::vector< size_t > > &removeFactorIndices={})
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
const Values & getLinearizationPoint() const
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16 fmod(const bfloat16 &a, const bfloat16 &b)
virtual Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const std::optional< std::vector< size_t > > &removeFactorIndices={})
static const double deltaT
Pose2 priorMean(0.0, 0.0, 0.0)
A Levenberg-Marquardt Batch Smoother that implements the Concurrent Filtering and Smoothing interface...
std::vector< float > Values
const KeyTimestampMap & timestamps() const
virtual void resize(size_t size)
Values calculateEstimate() const override
void synchronize(ConcurrentFilter &filter, ConcurrentSmoother &smoother)
void insert(Key j, const Value &val)
const Values & getLinearizationPoint() const
std::uint64_t Key
Integer nonlinear key type.