NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
sliding_window_node_adder.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef NODE_ADDERS_SLIDING_WINDOW_NODE_ADDER_H_
20 #define NODE_ADDERS_SLIDING_WINDOW_NODE_ADDER_H_
21 
23 #include <node_adders/node_adder.h>
24 
25 #include <gtsam/nonlinear/Marginals.h>
26 #include <gtsam/nonlinear/NonlinearFactorGraph.h>
27 
28 namespace node_adders {
29 // Base class node adder that maintains a sliding window of nodes.
31  public:
33 
34  // Slides the window, removes nodes older than oldest allowed time.
35  // Adds priors to the oldest remaining nodes using their marginalized covariances
36  // and removes old priors containing any key in old keys if param use_priors is true.
37  // Note: Old factor removal (other than starting priors) is handled in the graph optimizer.
38  // The oldest allowed timestamp is also determing by the graph optimizer based on
39  // the ideal oldest allowed timestamps of each node adder used in the graph.
40  virtual bool SlideWindow(const localization_common::Time oldest_allowed_timestamp,
41  const boost::optional<const gtsam::Marginals&>& marginals, const gtsam::KeyVector& old_keys,
42  const double huber_k, gtsam::NonlinearFactorGraph& factors) = 0;
43 
44  // Returns the oldest node time that should remain after SlideWindow is called.
45  virtual boost::optional<localization_common::Time> SlideWindowNewStartTime() const = 0;
46 
47  // Returns old node keys older than the oldest_allowed_time.
48  virtual gtsam::KeyVector OldKeys(const localization_common::Time oldest_allowed_time,
49  const gtsam::NonlinearFactorGraph& graph) const = 0;
50 
51  // Starting (oldest) timestamp of nodes in the node adder
52  virtual boost::optional<localization_common::Time> StartTime() const = 0;
53 
54  // End (latest) timestamp of nodes in the node adder
55  virtual boost::optional<localization_common::Time> EndTime() const = 0;
56 };
57 } // namespace node_adders
58 
59 #endif // NODE_ADDERS_SLIDING_WINDOW_NODE_ADDER_H_
node_adders::SlidingWindowNodeAdder::OldKeys
virtual gtsam::KeyVector OldKeys(const localization_common::Time oldest_allowed_time, const gtsam::NonlinearFactorGraph &graph) const =0
node_adders::NodeAdder
Definition: node_adder.h:31
node_adders::SlidingWindowNodeAdder
Definition: sliding_window_node_adder.h:30
node_adders
Definition: between_factor_node_adder_model.h:35
node_adders::SlidingWindowNodeAdder::~SlidingWindowNodeAdder
virtual ~SlidingWindowNodeAdder()
Definition: sliding_window_node_adder.h:32
node_adders::SlidingWindowNodeAdder::EndTime
virtual boost::optional< localization_common::Time > EndTime() const =0
node_adder.h
time.h
node_adders::SlidingWindowNodeAdder::SlideWindowNewStartTime
virtual boost::optional< localization_common::Time > SlideWindowNewStartTime() const =0
node_adders::SlidingWindowNodeAdder::StartTime
virtual boost::optional< localization_common::Time > StartTime() const =0
node_adders::SlidingWindowNodeAdder::SlideWindow
virtual bool SlideWindow(const localization_common::Time oldest_allowed_timestamp, const boost::optional< const gtsam::Marginals & > &marginals, const gtsam::KeyVector &old_keys, const double huber_k, gtsam::NonlinearFactorGraph &factors)=0
localization_common::Time
double Time
Definition: time.h:23