NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
timestamped_node_adder_model.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_TIMESTAMPED_NODE_ADDER_MODEL_H_
20 #define NODE_ADDERS_TIMESTAMPED_NODE_ADDER_MODEL_H_
21 
23 
24 #include <gtsam/inference/Key.h>
25 #include <gtsam/nonlinear/NonlinearFactorGraph.h>
26 
27 #include <vector>
28 
29 namespace node_adders {
30 // Handles adding priors and relative factors for a given node type.
31 // Generates these factors for provided timestamps.
32 // Required by TimestampedNodeAdder.
33 template <typename NodeType, typename NodesType>
35  public:
37  virtual ~TimestampedNodeAdderModel() = default;
38  // Adds prior factors for a given node using provided noise models.
39  virtual void AddPriors(const NodeType& node, const std::vector<gtsam::SharedNoiseModel>& noise_models,
40  const localization_common::Time timestamp, const NodesType& nodes,
41  gtsam::NonlinearFactorGraph& factors) const = 0;
42 
43  // Adds nodes for timestamp_b and connect it to the node at timestamp_a with relative factors.
44  virtual bool AddNodesAndRelativeFactors(const localization_common::Time timestamp_a,
45  const localization_common::Time timestamp_b, NodesType& nodes,
46  gtsam::NonlinearFactorGraph& factors) const = 0;
47 
48  // Adds relative factors between nodes at timestamp_a and timestamp_b.
49  virtual bool AddRelativeFactors(const localization_common::Time timestamp_a,
50  const localization_common::Time timestamp_b, const NodesType& nodes,
51  gtsam::NonlinearFactorGraph& factors) const = 0;
52 
53  // Returns whether a node can be added at timestamp or not.
54  virtual bool CanAddNode(const localization_common::Time timestamp) const = 0;
55 
56  // Remove relative adder model factors between nodes
57  virtual bool RemoveRelativeFactors(const localization_common::Time timestamp_a,
58  const localization_common::Time timestamp_b, const NodesType& nodes,
59  gtsam::NonlinearFactorGraph& factors) const = 0;
60 
61  protected:
62  // TODO(rsoussan): Add constructor to set these, template on params?
64 };
65 } // namespace node_adders
66 
67 #endif // NODE_ADDERS_TIMESTAMPED_NODE_ADDER_MODEL_H_
node_adders::TimestampedNodeAdderModel::AddNodesAndRelativeFactors
virtual bool AddNodesAndRelativeFactors(const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const =0
timestamped_node_adder_model_params.h
nodes
Definition: combined_nav_state_nodes.h:24
node_adders
Definition: between_factor_node_adder_model.h:35
node_adders::TimestampedNodeAdderModel::AddPriors
virtual void AddPriors(const NodeType &node, const std::vector< gtsam::SharedNoiseModel > &noise_models, const localization_common::Time timestamp, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const =0
node_adders::TimestampedNodeAdderModel::TimestampedNodeAdderModel
TimestampedNodeAdderModel(const TimestampedNodeAdderModelParams &params)
Definition: timestamped_node_adder_model.h:36
node_adders::TimestampedNodeAdderModel
Definition: timestamped_node_adder_model.h:34
node_adders::TimestampedNodeAdderModel::CanAddNode
virtual bool CanAddNode(const localization_common::Time timestamp) const =0
node_adders::TimestampedNodeAdderModel::RemoveRelativeFactors
virtual bool RemoveRelativeFactors(const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const =0
node_adders::TimestampedNodeAdderModelParams
Definition: timestamped_node_adder_model_params.h:24
node_adders::TimestampedNodeAdderModel::AddRelativeFactors
virtual bool AddRelativeFactors(const localization_common::Time timestamp_a, const localization_common::Time timestamp_b, const NodesType &nodes, gtsam::NonlinearFactorGraph &factors) const =0
localization_common::Time
double Time
Definition: time.h:23
node_adders::TimestampedNodeAdderModel::params_
TimestampedNodeAdderModelParams params_
Definition: timestamped_node_adder_model.h:63
node_adders::TimestampedNodeAdderModel::~TimestampedNodeAdderModel
virtual ~TimestampedNodeAdderModel()=default