NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
loc_factor_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 
19 #ifndef FACTOR_ADDERS_LOC_FACTOR_ADDER_PARAMS_H_
20 #define FACTOR_ADDERS_LOC_FACTOR_ADDER_PARAMS_H_
21 
23 
24 #include <gtsam/geometry/Cal3_S2.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/linear/NoiseModel.h>
27 
28 namespace factor_adders {
30  // Add pose prior factors using estimated pose from matched
31  // projections measurement.
33  // Add projections factor using matched projections.
35  // Add pose prior factors if all projection factors fail.
37  // Translation stddev noise for prior factors.
39  // Quaternion stddev noise for prior factors.
41  // Inversely scale noise with the number of matched projections when creating a pose factor.
43  // Scale projection noise with the square of the ratio of the average number of matches per measurement
44  // to the current number of matches when creating a projections factor.
45  // Yields lower noise for measurements with more than average matches.
47  // Scale projection factor noise using the inverse of the distance to a landmark.
49  // Relative pose noise scale.
51  // Relative projections noise scale.
53  // Max num projection factors to add for a matched projections measurement.
55  // Min number of matched projections to create a factor (prior or projection).
57  // Max projection error norm for a projection factor to be valid.
59  // Camera extrinsics.
60  gtsam::Pose3 body_T_cam;
61  // Camera intrinsics.
62  boost::shared_ptr<gtsam::Cal3_S2> cam_intrinsics;
63  // Camera noise used for projection factor noise.
64  gtsam::SharedIsotropic cam_noise;
65 };
66 } // namespace factor_adders
67 
68 #endif // FACTOR_ADDERS_LOC_FACTOR_ADDER_PARAMS_H_
factor_adders::LocFactorAdderParams::scale_pose_noise_with_num_landmarks
bool scale_pose_noise_with_num_landmarks
Definition: loc_factor_adder_params.h:42
factor_adders::LocFactorAdderParams::add_projection_factors
bool add_projection_factors
Definition: loc_factor_adder_params.h:34
factor_adders::LocFactorAdderParams::max_num_projection_factors
int max_num_projection_factors
Definition: loc_factor_adder_params.h:54
factor_adders::LocFactorAdderParams
Definition: loc_factor_adder_params.h:29
factor_adders::LocFactorAdderParams::scale_projection_noise_with_num_landmarks
bool scale_projection_noise_with_num_landmarks
Definition: loc_factor_adder_params.h:46
factor_adders::LocFactorAdderParams::pose_noise_scale
double pose_noise_scale
Definition: loc_factor_adder_params.h:50
factor_adders::LocFactorAdderParams::scale_projection_noise_with_landmark_distance
bool scale_projection_noise_with_landmark_distance
Definition: loc_factor_adder_params.h:48
factor_adders::LocFactorAdderParams::prior_translation_stddev
double prior_translation_stddev
Definition: loc_factor_adder_params.h:38
factor_adders::FactorAdderParams
Definition: factor_adder_params.h:23
factor_adders::LocFactorAdderParams::add_pose_priors
bool add_pose_priors
Definition: loc_factor_adder_params.h:32
factor_adders::LocFactorAdderParams::projection_noise_scale
double projection_noise_scale
Definition: loc_factor_adder_params.h:52
factor_adders::LocFactorAdderParams::cam_intrinsics
boost::shared_ptr< gtsam::Cal3_S2 > cam_intrinsics
Definition: loc_factor_adder_params.h:62
factor_adder_params.h
factor_adders::LocFactorAdderParams::body_T_cam
gtsam::Pose3 body_T_cam
Definition: loc_factor_adder_params.h:60
factor_adders::LocFactorAdderParams::max_valid_projection_error
double max_valid_projection_error
Definition: loc_factor_adder_params.h:58
factor_adders::LocFactorAdderParams::cam_noise
gtsam::SharedIsotropic cam_noise
Definition: loc_factor_adder_params.h:64
factor_adders::LocFactorAdderParams::prior_quaternion_stddev
double prior_quaternion_stddev
Definition: loc_factor_adder_params.h:40
factor_adders
Definition: depth_odometry_factor_adder.h:31
factor_adders::LocFactorAdderParams::add_prior_if_projection_factors_fail
bool add_prior_if_projection_factors_fail
Definition: loc_factor_adder_params.h:36
factor_adders::LocFactorAdderParams::min_num_matches_per_measurement
int min_num_matches_per_measurement
Definition: loc_factor_adder_params.h:56