NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
timestamped_node_adder_params.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 #ifndef NODE_ADDERS_TIMESTAMPED_NODE_ADDER_PARAMS_H_
19 #define NODE_ADDERS_TIMESTAMPED_NODE_ADDER_PARAMS_H_
20 
22 
23 #include <boost/serialization/serialization.hpp>
24 
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/linear/NoiseModel.h>
27 
28 #include <vector>
29 
30 namespace node_adders {
31 template <typename NodeType>
33  NodeType start_node;
34  std::vector<gtsam::SharedNoiseModel> start_noise_models;
35  double huber_k;
36  bool add_priors;
38  // Only kept if there are at least min_num_states and not more than max_num_states
40  // TODO(rsoussan): Rename states to nodes?
43 
44  private:
45  // Serialization function
46  friend class boost::serialization::access;
47  template <class ARCHIVE>
48  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
49  ar& BOOST_SERIALIZATION_NVP(start_node);
50  ar& BOOST_SERIALIZATION_NVP(start_noise_models);
51  ar& BOOST_SERIALIZATION_NVP(huber_k);
52  ar& BOOST_SERIALIZATION_NVP(add_priors);
53  ar& BOOST_SERIALIZATION_NVP(starting_time);
54  ar& BOOST_SERIALIZATION_NVP(ideal_duration);
55  ar& BOOST_SERIALIZATION_NVP(min_num_states);
56  ar& BOOST_SERIALIZATION_NVP(max_num_states);
57  }
58 };
59 } // namespace node_adders
60 
61 #endif // NODE_ADDERS_TIMESTAMPED_NODE_ADDER_PARAMS_H_
node_adders::TimestampedNodeAdderParams::starting_time
localization_common::Time starting_time
Definition: timestamped_node_adder_params.h:37
node_adders::TimestampedNodeAdderParams::ideal_duration
double ideal_duration
Definition: timestamped_node_adder_params.h:39
node_adders::TimestampedNodeAdderParams::start_node
NodeType start_node
Definition: timestamped_node_adder_params.h:33
node_adders::TimestampedNodeAdderParams::add_priors
bool add_priors
Definition: timestamped_node_adder_params.h:36
node_adders
Definition: between_factor_node_adder_model.h:35
node_adders::TimestampedNodeAdderParams::huber_k
double huber_k
Definition: timestamped_node_adder_params.h:35
node_adders::TimestampedNodeAdderParams::max_num_states
int max_num_states
Definition: timestamped_node_adder_params.h:42
time.h
node_adders::TimestampedNodeAdderParams::min_num_states
int min_num_states
Definition: timestamped_node_adder_params.h:41
node_adders::TimestampedNodeAdderParams::start_noise_models
std::vector< gtsam::SharedNoiseModel > start_noise_models
Definition: timestamped_node_adder_params.h:34
node_adders::TimestampedNodeAdderParams
Definition: timestamped_node_adder_params.h:32
localization_common::Time
double Time
Definition: time.h:23