NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_to_plane_icp_depth_odometry_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 #ifndef DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
19 #define DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
20 
23 
24 #include <pcl/features/integral_image_normal.h>
25 
26 namespace depth_odometry {
29  bool downsample;
31  // Organized normal estimation
33  pcl::IntegralImageNormalEstimation<pcl::PointXYZI, pcl::Normal>::NormalEstimationMethod normal_estimation_method;
37  // Normal space sampling
41 };
42 } // namespace depth_odometry
43 
44 #endif // DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_PARAMS_H_
depth_odometry::PointToPlaneICPDepthOdometryParams::normal_smoothing_size
double normal_smoothing_size
Definition: point_to_plane_icp_depth_odometry_params.h:36
depth_odometry::PointToPlaneICPDepthOdometryParams::use_depth_dependent_smoothing
bool use_depth_dependent_smoothing
Definition: point_to_plane_icp_depth_odometry_params.h:34
depth_odometry::PointToPlaneICPDepthOdometryParams::downsample
bool downsample
Definition: point_to_plane_icp_depth_odometry_params.h:29
depth_odometry
Definition: depth_image_features_and_points.h:34
depth_odometry::DepthOdometryParams
Definition: depth_odometry_params.h:22
depth_odometry::PointToPlaneICPDepthOdometryParams::max_depth_change_factor
double max_depth_change_factor
Definition: point_to_plane_icp_depth_odometry_params.h:35
depth_odometry::PointToPlaneICPDepthOdometryParams::use_normal_space_sampling
bool use_normal_space_sampling
Definition: point_to_plane_icp_depth_odometry_params.h:38
depth_odometry_params.h
point_to_plane_icp_params.h
depth_odometry::PointToPlaneICPDepthOdometryParams::downsample_leaf_size
double downsample_leaf_size
Definition: point_to_plane_icp_depth_odometry_params.h:30
depth_odometry::PointToPlaneICPDepthOdometryParams::icp
point_cloud_common::PointToPlaneICPParams icp
Definition: point_to_plane_icp_depth_odometry_params.h:28
point_cloud_common::PointToPlaneICPParams
Definition: point_to_plane_icp_params.h:22
depth_odometry::PointToPlaneICPDepthOdometryParams::num_samples
int num_samples
Definition: point_to_plane_icp_depth_odometry_params.h:40
depth_odometry::PointToPlaneICPDepthOdometryParams::normal_estimation_method
pcl::IntegralImageNormalEstimation< pcl::PointXYZI, pcl::Normal >::NormalEstimationMethod normal_estimation_method
Definition: point_to_plane_icp_depth_odometry_params.h:33
depth_odometry::PointToPlaneICPDepthOdometryParams::bins_per_axis
int bins_per_axis
Definition: point_to_plane_icp_depth_odometry_params.h:39
depth_odometry::PointToPlaneICPDepthOdometryParams
Definition: point_to_plane_icp_depth_odometry_params.h:27
depth_odometry::PointToPlaneICPDepthOdometryParams::use_organized_normal_estimation
bool use_organized_normal_estimation
Definition: point_to_plane_icp_depth_odometry_params.h:32