NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
vo_smart_projection_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_VO_SMART_PROJECTION_FACTOR_ADDER_PARAMS_H_
20 #define FACTOR_ADDERS_VO_SMART_PROJECTION_FACTOR_ADDER_PARAMS_H_
21 
24 
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/geometry/Cal3_S2.h>
27 #include <gtsam/linear/NoiseModel.h>
28 #include <gtsam/slam/SmartFactorParams.h>
29 
30 namespace factor_adders {
33  // Maximum number of smart factors to include in a graph at a time.
35  // Minimum number of points for a feature track to be used for a smart factor.
37  // Maximum number of points in a feature track to include in a smart factor.
39  // Minimum average deviation for points in a feature track to be used.
40  // A higher deviation provides a larger baseline between points and is less likely
41  // to yield numerical errors during triangulation and optimization.
43  // Use a robust loss for the factor.
44  bool robust;
45  // Minimum distance in image space between the latest measurement in a feature track
46  // and already included latest measurements in other feature tracks for the feature track
47  // to be used as a smart factor.
48  /* double feature_track_min_separation;*/
49  // If triangulation fails, use a rotation-only version of the smart factor.
50  // Otherwise, the smart factor is disabled.
52  // Attempt to fix smart factors that are invalid by removing individual measurements
53  // and if this fails measurement sequences.
55  // Scale the noise with the number of points, as a longer track the relies on a
56  // longer history of poses tends to have higher error
58  // Relative noise scale for all smart factors.
59  double noise_scale;
60  // Camera extrinsics.
61  gtsam::Pose3 body_T_cam;
62  // Camera intrinsics.
63  boost::shared_ptr<gtsam::Cal3_S2> cam_intrinsics;
64  // Camera noise.
65  gtsam::SharedIsotropic cam_noise;
66  // GTSAM Smart factor params, see GTSAM documentation and below for more details.
67  // enableEPI: Refine triangulation using Levenberg-Marquardt Optimization.
68  // verboseCheirality: Print error on cheirality errors
69  // landmarkDistanceThreshold: Maximum valid distance for a triangulated point.
70  // dynamicOutlierRejectionThreshold: Maximum valid reprojection error for a valid triangulated point.
71  // retriangulationThreshold: Equality threshold for poses in a smart factor to trigger retriangulation
72  // of a landmark point. If any of the poses vary by more than this threshold
73  // compared to their previous value, retriangulation is triggered.
74  gtsam::SmartProjectionParams smart_factor;
75 };
76 } // namespace factor_adders
77 
78 #endif // FACTOR_ADDERS_VO_SMART_PROJECTION_FACTOR_ADDER_PARAMS_H_
factor_adders::VoSmartProjectionFactorAdderParams::cam_intrinsics
boost::shared_ptr< gtsam::Cal3_S2 > cam_intrinsics
Definition: vo_smart_projection_factor_adder_params.h:63
factor_adders::VoSmartProjectionFactorAdderParams::scale_noise_with_num_points
bool scale_noise_with_num_points
Definition: vo_smart_projection_factor_adder_params.h:57
factor_adders::VoSmartProjectionFactorAdderParams::smart_factor
gtsam::SmartProjectionParams smart_factor
Definition: vo_smart_projection_factor_adder_params.h:74
factor_adders::VoSmartProjectionFactorAdderParams::rotation_only_fallback
bool rotation_only_fallback
Definition: vo_smart_projection_factor_adder_params.h:51
factor_adders::VoSmartProjectionFactorAdderParams::min_avg_distance_from_mean
double min_avg_distance_from_mean
Definition: vo_smart_projection_factor_adder_params.h:42
factor_adders::VoSmartProjectionFactorAdderParams
Definition: vo_smart_projection_factor_adder_params.h:31
factor_adders::VoSmartProjectionFactorAdderParams::robust
bool robust
Definition: vo_smart_projection_factor_adder_params.h:44
factor_adders::VoSmartProjectionFactorAdderParams::spaced_feature_tracker
vision_common::SpacedFeatureTrackerParams spaced_feature_tracker
Definition: vo_smart_projection_factor_adder_params.h:32
factor_adders::VoSmartProjectionFactorAdderParams::cam_noise
gtsam::SharedIsotropic cam_noise
Definition: vo_smart_projection_factor_adder_params.h:65
factor_adders::FactorAdderParams
Definition: factor_adder_params.h:23
vision_common::SpacedFeatureTrackerParams
Definition: spaced_feature_tracker_params.h:24
factor_adders::VoSmartProjectionFactorAdderParams::body_T_cam
gtsam::Pose3 body_T_cam
Definition: vo_smart_projection_factor_adder_params.h:61
factor_adders::VoSmartProjectionFactorAdderParams::min_num_points_per_factor
int min_num_points_per_factor
Definition: vo_smart_projection_factor_adder_params.h:36
factor_adder_params.h
spaced_feature_tracker_params.h
factor_adders::VoSmartProjectionFactorAdderParams::fix_invalid_factors
bool fix_invalid_factors
Definition: vo_smart_projection_factor_adder_params.h:54
factor_adders::VoSmartProjectionFactorAdderParams::max_num_points_per_factor
int max_num_points_per_factor
Definition: vo_smart_projection_factor_adder_params.h:38
factor_adders
Definition: depth_odometry_factor_adder.h:31
factor_adders::VoSmartProjectionFactorAdderParams::max_num_factors
int max_num_factors
Definition: vo_smart_projection_factor_adder_params.h:34
factor_adders::VoSmartProjectionFactorAdderParams::noise_scale
double noise_scale
Definition: vo_smart_projection_factor_adder_params.h:59