NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
point_cloud_with_known_correspondences_aligner.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 POINT_CLOUD_COMMON_POINT_CLOUD_WITH_KNOWN_CORRESPONDENCES_ALIGNER_H_
19 #define POINT_CLOUD_COMMON_POINT_CLOUD_WITH_KNOWN_CORRESPONDENCES_ALIGNER_H_
20 
23 
24 #include <Eigen/Core>
25 
26 #include <ceres/ceres.h>
27 #include <ceres/solver.h>
28 
29 #include <boost/optional.hpp>
30 
31 #include <vector>
32 
33 namespace point_cloud_common {
35  public:
37 
38  boost::optional<localization_common::PoseWithCovariance> Align(
39  const std::vector<Eigen::Vector3d>& source_points, const std::vector<Eigen::Vector3d>& target_points,
40  const Eigen::Isometry3d& initial_target_T_source_estimate,
41  const boost::optional<const std::vector<Eigen::Vector3d>&> source_normals = boost::none,
42  const boost::optional<const std::vector<Eigen::Vector3d>&> target_normals = boost::none) const;
43 
44  boost::optional<localization_common::PoseWithCovariance> ComputeRelativeTransform(
45  const std::vector<Eigen::Vector3d>& source_points, const std::vector<Eigen::Vector3d>& target_points,
46  const boost::optional<const std::vector<Eigen::Vector3d>&> source_normals = boost::none,
47  const boost::optional<const std::vector<Eigen::Vector3d>&> target_normals = boost::none,
48  const Eigen::Isometry3d& initial_target_T_source_estimate = Eigen::Isometry3d::Identity()) const;
49 
50  boost::optional<localization_common::PoseWithCovariance> ComputeRelativeTransform(
51  const std::vector<Eigen::Vector3d>& source_points, const std::vector<Eigen::Vector3d>& target_points,
52  const Eigen::Isometry3d& initial_target_T_source_estimate = Eigen::Isometry3d::Identity()) const;
53 
54  private:
55  boost::optional<localization_common::PoseCovariance> Covariance(const double* const target_T_source_data,
56  ceres::Problem& problem) const;
57 
59 };
60 } // namespace point_cloud_common
61 
62 #endif // POINT_CLOUD_COMMON_POINT_CLOUD_WITH_KNOWN_CORRESPONDENCES_ALIGNER_H_
point_cloud_common
Definition: icp_correspondences.h:25
pose_with_covariance.h
point_cloud_common::PointCloudWithKnownCorrespondencesAligner::Align
boost::optional< localization_common::PoseWithCovariance > Align(const std::vector< Eigen::Vector3d > &source_points, const std::vector< Eigen::Vector3d > &target_points, const Eigen::Isometry3d &initial_target_T_source_estimate, const boost::optional< const std::vector< Eigen::Vector3d > & > source_normals=boost::none, const boost::optional< const std::vector< Eigen::Vector3d > & > target_normals=boost::none) const
Definition: point_cloud_with_known_correspondences_aligner.cc:34
point_cloud_common::PointCloudWithKnownCorrespondencesAlignerParams
Definition: point_cloud_with_known_correspondences_aligner_params.h:22
point_cloud_common::PointCloudWithKnownCorrespondencesAligner::ComputeRelativeTransform
boost::optional< localization_common::PoseWithCovariance > ComputeRelativeTransform(const std::vector< Eigen::Vector3d > &source_points, const std::vector< Eigen::Vector3d > &target_points, const boost::optional< const std::vector< Eigen::Vector3d > & > source_normals=boost::none, const boost::optional< const std::vector< Eigen::Vector3d > & > target_normals=boost::none, const Eigen::Isometry3d &initial_target_T_source_estimate=Eigen::Isometry3d::Identity()) const
Definition: point_cloud_with_known_correspondences_aligner.cc:90
point_cloud_common::PointCloudWithKnownCorrespondencesAligner
Definition: point_cloud_with_known_correspondences_aligner.h:34
localization_common::Isometry3d
Eigen::Isometry3d Isometry3d(const Eigen::Vector3d &translation, const RotationType &rotation)
Definition: utilities.h:226
point_cloud_with_known_correspondences_aligner_params.h
point_cloud_common::PointCloudWithKnownCorrespondencesAligner::PointCloudWithKnownCorrespondencesAligner
PointCloudWithKnownCorrespondencesAligner(const PointCloudWithKnownCorrespondencesAlignerParams &params)
Definition: point_cloud_with_known_correspondences_aligner.cc:30