lidar_measurement_model_likelihood.cpp
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 #include <algorithm>
31 #include <cmath>
32 #include <string>
33 #include <vector>
34 
35 #include <ros/ros.h>
36 
37 #include <pcl/point_types.h>
38 #include <pcl_ros/point_cloud.h>
39 
40 #include <mcl_3dl/pf.h>
42 #include <mcl_3dl/point_types.h>
43 #include <mcl_3dl/vec3.h>
44 
46 
47 namespace mcl_3dl
48 {
50  const ros::NodeHandle& nh,
51  const std::string& name)
52 {
53  ros::NodeHandle pnh(nh, name);
54 
55  int num_points, num_points_global;
56  pnh.param("num_points", num_points, 96);
57  pnh.param("num_points_global", num_points_global, 8);
58  num_points_default_ = num_points_ = num_points;
59  num_points_global_ = num_points_global;
60 
61  double clip_near, clip_far;
62  pnh.param("clip_near", clip_near, 0.5);
63  pnh.param("clip_far", clip_far, 10.0);
64  clip_near_sq_ = clip_near * clip_near;
65  clip_far_sq_ = clip_far * clip_far;
66 
67  double clip_z_min, clip_z_max;
68  pnh.param("clip_z_min", clip_z_min, -2.0);
69  pnh.param("clip_z_max", clip_z_max, 2.0);
70  clip_z_min_ = clip_z_min;
71  clip_z_max_ = clip_z_max;
72 
73  double match_weight;
74  pnh.param("match_weight", match_weight, 5.0);
75  match_weight_ = match_weight;
76 
77  double match_dist_min, match_dist_flat;
78  pnh.param("match_dist_min", match_dist_min, 0.2);
79  pnh.param("match_dist_flat", match_dist_flat, 0.05);
80  match_dist_min_ = match_dist_min;
81  match_dist_flat_ = match_dist_flat;
82 }
84  const size_t num_particles,
85  const size_t current_num_particles)
86 {
87  if (current_num_particles <= num_particles)
88  {
90  return;
91  }
92  size_t num = num_points_default_ * num_particles / current_num_particles;
93  if (num < num_points_global_)
94  num = num_points_global_;
95 
96  num_points_ = num;
97 }
98 
99 typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr
101  const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc) const
102 {
103  const auto local_points_filter = [this](const LidarMeasurementModelBase::PointType& p)
104  {
105  if (p.x * p.x + p.y * p.y > clip_far_sq_)
106  return true;
107  if (p.x * p.x + p.y * p.y < clip_near_sq_)
108  return true;
109  if (p.z < clip_z_min_ || clip_z_max_ < p.z)
110  return true;
111  return false;
112  };
113  pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_filtered(
114  new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
115  *pc_filtered = *pc;
116  pc_filtered->erase(
117  std::remove_if(pc_filtered->begin(), pc_filtered->end(), local_points_filter), pc_filtered->end());
118  pc_filtered->width = 1;
119  pc_filtered->height = pc_filtered->points.size();
120 
121  return sampler_->sample(pc_filtered, num_points_);
122 }
123 
126  const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc,
127  const std::vector<Vec3>& origins,
128  const State6DOF& s) const
129 {
130  if (!pc)
131  return LidarMeasurementResult(1, 0);
132  if (pc->size() == 0)
133  return LidarMeasurementResult(1, 0);
134  pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_particle(
135  new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
136  std::vector<int> id(1);
137  std::vector<float> sqdist(1);
138 
139  float score_like = 0;
140  *pc_particle = *pc;
141  s.transform(*pc_particle);
142  size_t num = 0;
143  for (auto& p : pc_particle->points)
144  {
145  if (kdtree->radiusSearch(p, match_dist_min_, id, sqdist, 1))
146  {
147  const float dist = match_dist_min_ - std::max(std::sqrt(sqdist[0]), match_dist_flat_);
148  if (dist < 0.0)
149  continue;
150 
151  score_like += dist * match_weight_;
152  num++;
153  }
154  }
155  const float match_ratio = static_cast<float>(num) / pc_particle->points.size();
156 
157  return LidarMeasurementResult(score_like, match_ratio);
158 }
159 } // namespace mcl_3dl
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
void transform(pcl::PointCloud< PointType > &pc) const
Definition: state_6dof.h:188
std::shared_ptr< ChunkedKdtree > Ptr
void setGlobalLocalizationStatus(const size_t num_particles, const size_t current_num_particles)
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
void loadConfig(const ros::NodeHandle &nh, const std::string &name)
int radiusSearch(const POINT_TYPE &p, const float &radius, std::vector< int > &id, std::vector< float > &dist_sq, const size_t &num)
bool param(const std::string &param_name, T &param_val, const T &default_val) const


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29