include
mcl_3dl
lidar_measurement_models
lidar_measurement_model_likelihood.h
Go to the documentation of this file.
1
/*
2
* Copyright (c) 2018, the mcl_3dl authors
3
* All rights reserved.
4
*
5
* Redistribution and use in source and binary forms, with or without
6
* modification, are permitted provided that the following conditions are met:
7
*
8
* * Redistributions of source code must retain the above copyright
9
* notice, this list of conditions and the following disclaimer.
10
* * Redistributions in binary form must reproduce the above copyright
11
* notice, this list of conditions and the following disclaimer in the
12
* documentation and/or other materials provided with the distribution.
13
* * Neither the name of the copyright holder nor the names of its
14
* contributors may be used to endorse or promote products derived from
15
* this software without specific prior written permission.
16
*
17
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27
* POSSIBILITY OF SUCH DAMAGE.
28
*/
29
30
#ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
31
#define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
32
33
#include <memory>
34
#include <string>
35
#include <vector>
36
37
#include <
ros/ros.h
>
38
39
#include <pcl/point_types.h>
40
#include <
pcl_ros/point_cloud.h
>
41
42
#include <
mcl_3dl/chunked_kdtree.h
>
43
#include <
mcl_3dl/lidar_measurement_model_base.h
>
44
#include <
mcl_3dl/pf.h
>
45
#include <
mcl_3dl/point_cloud_random_sampler.h
>
46
#include <
mcl_3dl/vec3.h
>
47
48
namespace
mcl_3dl
49
{
50
class
LidarMeasurementModelLikelihood
:
public
LidarMeasurementModelBase
51
{
52
private
:
53
size_t
num_points_
;
54
size_t
num_points_default_
;
55
size_t
num_points_global_
;
56
float
clip_far_sq_
;
57
float
clip_near_sq_
;
58
float
clip_z_min_
;
59
float
clip_z_max_
;
60
float
match_weight_
;
61
float
match_dist_min_
;
62
float
match_dist_flat_
;
63
64
public
:
65
inline
float
getMaxSearchRange
()
const
66
{
67
return
match_dist_min_
;
68
}
69
70
void
loadConfig
(
71
const
ros::NodeHandle
& nh,
72
const
std::string& name);
73
void
setGlobalLocalizationStatus
(
74
const
size_t
num_particles,
75
const
size_t
current_num_particles);
76
pcl::PointCloud<PointType>::Ptr
filter
(
77
const
pcl::PointCloud<PointType>::ConstPtr& pc)
const
;
78
LidarMeasurementResult
measure
(
79
ChunkedKdtree<PointType>::Ptr
& kdtree,
80
const
pcl::PointCloud<PointType>::ConstPtr& pc,
81
const
std::vector<Vec3>& origins,
82
const
State6DOF
& s)
const
;
83
};
84
}
// namespace mcl_3dl
85
86
#endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H
mcl_3dl::LidarMeasurementModelLikelihood::setGlobalLocalizationStatus
void setGlobalLocalizationStatus(const size_t num_particles, const size_t current_num_particles)
Definition:
lidar_measurement_model_likelihood.cpp:83
mcl_3dl::LidarMeasurementModelLikelihood::match_dist_flat_
float match_dist_flat_
Definition:
lidar_measurement_model_likelihood.h:62
pf.h
mcl_3dl::ChunkedKdtree::Ptr
std::shared_ptr< ChunkedKdtree > Ptr
Definition:
chunked_kdtree.h:49
mcl_3dl::LidarMeasurementModelLikelihood
Definition:
lidar_measurement_model_likelihood.h:50
ros.h
mcl_3dl::LidarMeasurementModelLikelihood::filter
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
Definition:
lidar_measurement_model_likelihood.cpp:100
mcl_3dl::LidarMeasurementModelLikelihood::match_dist_min_
float match_dist_min_
Definition:
lidar_measurement_model_likelihood.h:61
mcl_3dl::LidarMeasurementModelLikelihood::num_points_global_
size_t num_points_global_
Definition:
lidar_measurement_model_likelihood.h:55
mcl_3dl::LidarMeasurementResult
Definition:
lidar_measurement_model_base.h:52
mcl_3dl::LidarMeasurementModelLikelihood::num_points_default_
size_t num_points_default_
Definition:
lidar_measurement_model_likelihood.h:54
mcl_3dl::LidarMeasurementModelLikelihood::measure
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
Definition:
lidar_measurement_model_likelihood.cpp:124
point_cloud_random_sampler.h
vec3.h
point_cloud.h
mcl_3dl::LidarMeasurementModelBase
Definition:
lidar_measurement_model_base.h:64
mcl_3dl::LidarMeasurementModelLikelihood::clip_z_max_
float clip_z_max_
Definition:
lidar_measurement_model_likelihood.h:59
mcl_3dl::LidarMeasurementModelLikelihood::num_points_
size_t num_points_
Definition:
lidar_measurement_model_likelihood.h:53
lidar_measurement_model_base.h
mcl_3dl
Definition:
chunked_kdtree.h:43
mcl_3dl::LidarMeasurementModelLikelihood::clip_near_sq_
float clip_near_sq_
Definition:
lidar_measurement_model_likelihood.h:57
mcl_3dl::LidarMeasurementModelLikelihood::getMaxSearchRange
float getMaxSearchRange() const
Definition:
lidar_measurement_model_likelihood.h:65
mcl_3dl::LidarMeasurementModelLikelihood::loadConfig
void loadConfig(const ros::NodeHandle &nh, const std::string &name)
Definition:
lidar_measurement_model_likelihood.cpp:49
mcl_3dl::LidarMeasurementModelLikelihood::clip_z_min_
float clip_z_min_
Definition:
lidar_measurement_model_likelihood.h:58
mcl_3dl::LidarMeasurementModelLikelihood::match_weight_
float match_weight_
Definition:
lidar_measurement_model_likelihood.h:60
chunked_kdtree.h
mcl_3dl::State6DOF
Definition:
state_6dof.h:49
mcl_3dl::LidarMeasurementModelLikelihood::clip_far_sq_
float clip_far_sq_
Definition:
lidar_measurement_model_likelihood.h:56
ros::NodeHandle
mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04