Autoware.Auto
ndt_voxel.hpp
Go to the documentation of this file.
1
// Copyright 2019 the Autoware Foundation
2
//
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
// you may not use this file except in compliance with the License.
5
// You may obtain a copy of the License at
6
//
7
// http://www.apache.org/licenses/LICENSE-2.0
8
//
9
// Unless required by applicable law or agreed to in writing, software
10
// distributed under the License is distributed on an "AS IS" BASIS,
11
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12
// See the License for the specific language governing permissions and
13
// limitations under the License.
14
//
15
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16
17
#ifndef NDT__NDT_VOXEL_HPP_
18
#define NDT__NDT_VOXEL_HPP_
19
20
#include <
ndt/ndt_common.hpp
>
21
#include <experimental/optional>
22
#include <
voxel_grid/voxels.hpp
>
23
#include "
common/types.hpp
"
24
25
using
autoware::common::types::bool8_t
;
26
27
namespace
autoware
28
{
29
namespace
localization
30
{
31
namespace
ndt
32
{
33
34
enum class
Invertibility
35
{
36
INVERTIBLE
,
37
NOT_INVERTIBLE
,
38
UNKNOWN
39
};
40
44
class
NDT_PUBLIC
DynamicNDTVoxel
45
{
46
public
:
47
using
Point
= Eigen::Vector3d;
48
using
Cov
= Eigen::Matrix3d;
49
DynamicNDTVoxel
();
50
51
// TODO(yunus.caliskan): make this configurable.
52
// Number of points a voxel should have to count as occupied. Set to the dimension of a 3D point.
53
static
constexpr uint32_t NUM_POINT_THRESHOLD = 3U;
54
59
void
add_observation(
const
Point
& pt);
60
63
bool8_t
try_stabilize();
64
67
bool8_t
usable() const noexcept;
68
73
const
Cov
& covariance() const;
74
78
std::experimental::optional<
Cov
> inverse_covariance() const;
79
82
const
Point
& centroid() const;
83
86
uint64_t count() const noexcept;
87
88
private:
89
Point
m_centroid;
90
Cov
m_M2;
// Used in covariance computation.
91
Cov
m_covariance;
92
Invertibility
m_invertible{
Invertibility::UNKNOWN
};
93
uint64_t m_num_points{0U};
94
};
95
98
class
NDT_PUBLIC
StaticNDTVoxel
99
{
100
public
:
101
using
Point
= Eigen::Vector3d;
102
using
Cov
= Eigen::Matrix3d;
104
StaticNDTVoxel
();
105
109
StaticNDTVoxel
(
const
Point
& centroid,
const
Cov
& inv_covariance);
110
113
Cov
covariance()
const
;
116
const
Point
& centroid()
const
;
117
120
const
Cov
& inverse_covariance()
const
;
121
124
bool8_t
usable() const noexcept;
125
126
private:
127
Point
m_centroid;
128
Cov
m_inv_covariance;
129
bool8_t
m_occupied{
false
};
130
};
131
}
// namespace ndt
132
}
// namespace localization
133
}
// namespace autoware
134
135
#endif // NDT__NDT_VOXEL_HPP_
autoware::localization::ndt::Invertibility::UNKNOWN
@ UNKNOWN
voxels.hpp
This file defines children and specializations of the Voxel class.
autoware::localization::ndt::StaticNDTVoxel::Point
Eigen::Vector3d Point
Definition:
ndt_voxel.hpp:101
types.hpp
This file includes common type definition.
autoware::localization::ndt::Invertibility::NOT_INVERTIBLE
@ NOT_INVERTIBLE
autoware::localization::ndt::StaticNDTVoxel
Definition:
ndt_voxel.hpp:98
autoware::localization::ndt::Invertibility
Invertibility
Definition:
ndt_voxel.hpp:34
autoware::common::types::bool8_t
bool bool8_t
Definition:
types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition:
quick_sort.hpp:24
ndt_common.hpp
autoware::localization::ndt::StaticNDTVoxel::Cov
Eigen::Matrix3d Cov
Definition:
ndt_voxel.hpp:102
autoware::localization::ndt::DynamicNDTVoxel
Definition:
ndt_voxel.hpp:44
autoware::localization::ndt::DynamicNDTVoxel::Point
Eigen::Vector3d Point
Definition:
ndt_voxel.hpp:47
autoware::localization::ndt::Invertibility::INVERTIBLE
@ INVERTIBLE
autoware::localization::ndt::DynamicNDTVoxel::Cov
Eigen::Matrix3d Cov
Definition:
ndt_voxel.hpp:48