NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
depth_odometry_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_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
20 #define FACTOR_ADDERS_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
21 
23 
24 #include <gtsam/geometry/Pose3.h>
25 
26 namespace factor_adders {
38  gtsam::Pose3 body_T_sensor;
39 };
40 } // namespace factor_adders
41 
42 #endif // FACTOR_ADDERS_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
factor_adders::DepthOdometryFactorAdderParams::body_T_sensor
gtsam::Pose3 body_T_sensor
Definition: depth_odometry_factor_adder_params.h:38
factor_adders::DepthOdometryFactorAdderParams::reject_large_translation_norm
bool reject_large_translation_norm
Definition: depth_odometry_factor_adder_params.h:33
factor_adders::DepthOdometryFactorAdderParams::max_num_points_between_factors
int max_num_points_between_factors
Definition: depth_odometry_factor_adder_params.h:37
factor_adders::DepthOdometryFactorAdderParams::pose_covariance_scale
double pose_covariance_scale
Definition: depth_odometry_factor_adder_params.h:28
factor_adders::DepthOdometryFactorAdderParams::point_to_point_error_threshold
double point_to_point_error_threshold
Definition: depth_odometry_factor_adder_params.h:36
factor_adders::DepthOdometryFactorAdderParams::scale_point_between_factors_with_inverse_distance
bool scale_point_between_factors_with_inverse_distance
Definition: depth_odometry_factor_adder_params.h:31
factor_adders::FactorAdderParams
Definition: factor_adder_params.h:23
factor_adders::DepthOdometryFactorAdderParams::scale_point_between_factors_with_estimate_error
bool scale_point_between_factors_with_estimate_error
Definition: depth_odometry_factor_adder_params.h:32
factor_adders::DepthOdometryFactorAdderParams
Definition: depth_odometry_factor_adder_params.h:27
factor_adder_params.h
factor_adders::DepthOdometryFactorAdderParams::pose_translation_norm_threshold
double pose_translation_norm_threshold
Definition: depth_odometry_factor_adder_params.h:34
factor_adders
Definition: depth_odometry_factor_adder.h:31
factor_adders::DepthOdometryFactorAdderParams::point_noise_scale
double point_noise_scale
Definition: depth_odometry_factor_adder_params.h:29
factor_adders::DepthOdometryFactorAdderParams::use_points_between_factor
bool use_points_between_factor
Definition: depth_odometry_factor_adder_params.h:30
factor_adders::DepthOdometryFactorAdderParams::reject_large_point_to_point_error
bool reject_large_point_to_point_error
Definition: depth_odometry_factor_adder_params.h:35