 |
NASA Astrobee Robot Software
Astrobee Version:
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
22 #ifndef TUTORIAL_EXAMPLES_SIMPLE_ODOMETRY_PARAMS_H_
23 #define TUTORIAL_EXAMPLES_SIMPLE_ODOMETRY_PARAMS_H_
51 Eigen::Vector3d::Zero();
79 .slide_window_before_optimization =
true;
90 sliding_window_graph_optimizer::
91 SlidingWindowGraphOptimizerParams
96 #endif // TUTORIAL_EXAMPLES_SIMPLE_ODOMETRY_PARAMS_H_
imu_integration::ImuIntegratorParams imu_integrator
Definition: combined_nav_state_node_adder_model_params.h:29
localization_common::Time starting_time
Definition: timestamped_node_adder_params.h:37
double ideal_duration
Definition: timestamped_node_adder_params.h:39
double integration_variance
Definition: imu_integrator_params.h:38
node_adders::CombinedNavStateNodeAdderModel::Params combined_nav_state_node_adder_model
Definition: simple_odometry_params.h:88
Definition: nonlinear_optimizer_params.h:24
bool add_priors
Definition: timestamped_node_adder_params.h:36
Definition: combined_nav_state.h:48
double accel_sigma
Definition: imu_integrator_params.h:35
Definition: combined_nav_state_node_adder_model_params.h:28
optimizers::NonlinearOptimizerParams nonlinear_optimizer
Definition: simple_odometry_params.h:89
bool use_ceres_params
Definition: nonlinear_optimizer_params.h:30
int max_iterations
Definition: nonlinear_optimizer_params.h:26
double gyro_bias_sigma
Definition: imu_integrator_params.h:37
Definition: relative_pose_factor_adder_params.h:25
node_adders::TimestampedNodeAdderParams< localization_common::CombinedNavState > combined_nav_state_node_adder
Definition: simple_odometry_params.h:86
double gyro_sigma
Definition: imu_integrator_params.h:34
double accel_bias_sigma
Definition: imu_integrator_params.h:36
double huber_k
Definition: timestamped_node_adder_params.h:35
bool enabled
Definition: factor_adder_params.h:24
int max_num_states
Definition: timestamped_node_adder_params.h:42
Definition: sliding_window_graph_optimizer.h:32
bool verbose
Definition: nonlinear_optimizer_params.h:28
sliding_window_graph_optimizer::SlidingWindowGraphOptimizerParams sliding_window_graph_optimizer
Definition: simple_odometry_params.h:92
std::string marginals_factorization
Definition: optimizer_params.h:26
Definition: simple_localizer.h:32
gtsam::Vector3 gravity
Definition: imu_integrator_params.h:30
double huber_k
Definition: timestamped_node_adder_model_params.h:25
gtsam::Pose3 body_T_imu
Definition: imu_integrator_params.h:31
double bias_acc_omega_int
Definition: imu_integrator_params.h:39
int min_num_states
Definition: timestamped_node_adder_params.h:41
Definition: timestamped_node_adder_params.h:32
double huber_k
Definition: factor_adder_params.h:25
Definition: simple_odometry_params.h:33
factor_adders::RelativePoseFactorAdderParams relative_pose_factor_adder
Definition: simple_odometry_params.h:83
SimpleOdometryParams()
Definition: simple_odometry_params.h:37