NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
icp_correspondences.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_ICP_CORRESPONDENCES_H_
19
#define POINT_CLOUD_COMMON_ICP_CORRESPONDENCES_H_
20
21
#include <
ff_common/eigen_vectors.h
>
22
23
#include <vector>
24
25
namespace
point_cloud_common
{
26
struct
ICPCorrespondences
{
27
ICPCorrespondences
(
const
std::vector<Eigen::Vector3d>&
source_points
,
28
const
std::vector<Eigen::Vector3d>&
target_points
,
29
const
std::vector<Eigen::Vector3d>&
target_normals
)
30
:
source_points
(
source_points
),
target_points
(
target_points
),
target_normals
(
target_normals
) {}
31
size_t
size
()
const
{
return
source_points
.size(); }
32
33
std::vector<Eigen::Vector3d>
source_points
;
34
std::vector<Eigen::Vector3d>
target_points
;
35
std::vector<Eigen::Vector3d>
target_normals
;
36
};
37
}
// namespace point_cloud_common
38
39
#endif // POINT_CLOUD_COMMON_ICP_CORRESPONDENCES_H_
point_cloud_common
Definition:
icp_correspondences.h:25
point_cloud_common::ICPCorrespondences
Definition:
icp_correspondences.h:26
point_cloud_common::ICPCorrespondences::ICPCorrespondences
ICPCorrespondences(const std::vector< Eigen::Vector3d > &source_points, const std::vector< Eigen::Vector3d > &target_points, const std::vector< Eigen::Vector3d > &target_normals)
Definition:
icp_correspondences.h:27
point_cloud_common::ICPCorrespondences::source_points
std::vector< Eigen::Vector3d > source_points
Definition:
icp_correspondences.h:33
point_cloud_common::ICPCorrespondences::target_normals
std::vector< Eigen::Vector3d > target_normals
Definition:
icp_correspondences.h:35
eigen_vectors.h
point_cloud_common::ICPCorrespondences::size
size_t size() const
Definition:
icp_correspondences.h:31
point_cloud_common::ICPCorrespondences::target_points
std::vector< Eigen::Vector3d > target_points
Definition:
icp_correspondences.h:34