|
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.
18 #ifndef DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
19 #define DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
24 #include <pcl/features/integral_image_normal.h>
44 #endif // DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
double normal_smoothing_size
Definition: point_to_plane_icp_depth_odometry_params.h:36
bool use_depth_dependent_smoothing
Definition: point_to_plane_icp_depth_odometry_params.h:34
bool downsample
Definition: point_to_plane_icp_depth_odometry_params.h:29
Definition: depth_image_features_and_points.h:34
Definition: depth_odometry_params.h:22
double max_depth_change_factor
Definition: point_to_plane_icp_depth_odometry_params.h:35
bool use_normal_space_sampling
Definition: point_to_plane_icp_depth_odometry_params.h:38
double downsample_leaf_size
Definition: point_to_plane_icp_depth_odometry_params.h:30
point_cloud_common::PointToPlaneICPParams icp
Definition: point_to_plane_icp_depth_odometry_params.h:28
Definition: point_to_plane_icp_params.h:22
int num_samples
Definition: point_to_plane_icp_depth_odometry_params.h:40
pcl::IntegralImageNormalEstimation< pcl::PointXYZI, pcl::Normal >::NormalEstimationMethod normal_estimation_method
Definition: point_to_plane_icp_depth_odometry_params.h:33
int bins_per_axis
Definition: point_to_plane_icp_depth_odometry_params.h:39
Definition: point_to_plane_icp_depth_odometry_params.h:27
bool use_organized_normal_estimation
Definition: point_to_plane_icp_depth_odometry_params.h:32