|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef FACTOR_ADDERS_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
20 #define FACTOR_ADDERS_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
24 #include <gtsam/geometry/Pose3.h>
42 #endif // FACTOR_ADDERS_DEPTH_ODOMETRY_FACTOR_ADDER_PARAMS_H_
gtsam::Pose3 body_T_sensor
Definition: depth_odometry_factor_adder_params.h:38
bool reject_large_translation_norm
Definition: depth_odometry_factor_adder_params.h:33
int max_num_points_between_factors
Definition: depth_odometry_factor_adder_params.h:37
double pose_covariance_scale
Definition: depth_odometry_factor_adder_params.h:28
double point_to_point_error_threshold
Definition: depth_odometry_factor_adder_params.h:36
bool scale_point_between_factors_with_inverse_distance
Definition: depth_odometry_factor_adder_params.h:31
Definition: factor_adder_params.h:23
bool scale_point_between_factors_with_estimate_error
Definition: depth_odometry_factor_adder_params.h:32
Definition: depth_odometry_factor_adder_params.h:27
double pose_translation_norm_threshold
Definition: depth_odometry_factor_adder_params.h:34
Definition: depth_odometry_factor_adder.h:31
double point_noise_scale
Definition: depth_odometry_factor_adder_params.h:29
bool use_points_between_factor
Definition: depth_odometry_factor_adder_params.h:30
bool reject_large_point_to_point_error
Definition: depth_odometry_factor_adder_params.h:35