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.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_H_
19 #define DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_H_
20 
25 
26 namespace depth_odometry {
28  public:
30  boost::optional<PoseWithCovarianceAndCorrespondences> DepthImageCallback(
31  const localization_measurements::DepthImageMeasurement& depth_image_measurement) final;
32  boost::optional<PoseWithCovarianceAndCorrespondences> DepthImageCallbackWithEstimate(
33  const localization_measurements::DepthImageMeasurement& depth_image_measurement,
34  const boost::optional<Eigen::Isometry3d&> target_T_source_initial_estimate = boost::none);
35  const PointToPlaneICPDepthOdometryParams& params() const { return params_; }
36 
37  private:
38  pcl::PointCloud<pcl::PointXYZINormal>::Ptr DownsampleAndFilterCloud(
39  const pcl::PointCloud<pcl::PointXYZI>::Ptr& cloud) const;
40 
43  pcl::PointCloud<pcl::PointXYZINormal>::Ptr previous_point_cloud_with_normals_;
44  pcl::PointCloud<pcl::PointXYZINormal>::Ptr latest_point_cloud_with_normals_;
45  localization_common::Time previous_timestamp_;
46  localization_common::Time latest_timestamp_;
47 };
48 } // namespace depth_odometry
49 
50 #endif // DEPTH_ODOMETRY_POINT_TO_PLANE_ICP_DEPTH_ODOMETRY_H_
depth_odometry::PointToPlaneICPDepthOdometry
Definition: point_to_plane_icp_depth_odometry.h:27
point_to_plane_icp.h
depth_odometry::PointToPlaneICPDepthOdometry::DepthImageCallback
boost::optional< PoseWithCovarianceAndCorrespondences > DepthImageCallback(const localization_measurements::DepthImageMeasurement &depth_image_measurement) final
Definition: point_to_plane_icp_depth_odometry.cc:65
pose_with_covariance_and_correspondences.h
point_to_plane_icp_depth_odometry_params.h
depth_odometry
Definition: depth_image_features_and_points.h:34
depth_odometry::DepthOdometry
Definition: depth_odometry.h:29
depth_odometry.h
depth_odometry::PointToPlaneICPDepthOdometry::PointToPlaneICPDepthOdometry
PointToPlaneICPDepthOdometry(const PointToPlaneICPDepthOdometryParams &params)
Definition: point_to_plane_icp_depth_odometry.cc:29
depth_odometry::PointToPlaneICPDepthOdometry::DepthImageCallbackWithEstimate
boost::optional< PoseWithCovarianceAndCorrespondences > DepthImageCallbackWithEstimate(const localization_measurements::DepthImageMeasurement &depth_image_measurement, const boost::optional< Eigen::Isometry3d & > target_T_source_initial_estimate=boost::none)
Definition: point_to_plane_icp_depth_odometry.cc:70
point_cloud_common::PointToPlaneICP< pcl::PointXYZINormal >
localization_measurements::DepthImageMeasurement
Definition: depth_image_measurement.h:32
depth_odometry::PointToPlaneICPDepthOdometry::params
const PointToPlaneICPDepthOdometryParams & params() const
Definition: point_to_plane_icp_depth_odometry.h:35
localization_common::Time
double Time
Definition: time.h:23
depth_odometry::PointToPlaneICPDepthOdometryParams
Definition: point_to_plane_icp_depth_odometry_params.h:27