lidar_measurement_model_beam.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 <memory>
33 #include <string>
34 #include <vector>
35 
36 #include <ros/ros.h>
37 
38 #include <pcl/point_types.h>
39 #include <pcl_ros/point_cloud.h>
40 
41 #include <mcl_3dl/pf.h>
43 #include <mcl_3dl/point_types.h>
44 #include <mcl_3dl/raycast.h>
47 #include <mcl_3dl/vec3.h>
48 
50 
51 namespace mcl_3dl
52 {
54  const float map_grid_x, const float map_grid_y, const float map_grid_z)
55  : map_grid_x_(map_grid_x)
56  , map_grid_y_(map_grid_y)
57  , map_grid_z_(map_grid_z)
58 {
59  // FIXME(at-wat): remove NOLINT after clang-format or roslint supports it
60  search_range_ = std::max({ map_grid_x_, map_grid_y_, map_grid_z_ }) * 4; // NOLINT(whitespace/braces)
61 }
62 
64  const ros::NodeHandle& nh,
65  const std::string& name)
66 {
67  ros::NodeHandle pnh(nh, name);
68 
69  int num_points, num_points_global;
70  pnh.param("num_points", num_points, 3);
71  pnh.param("num_points_global", num_points_global, 0);
72  num_points_default_ = num_points_ = num_points;
73  num_points_global_ = num_points_global;
74 
75  double clip_near, clip_far;
76  pnh.param("clip_near", clip_near, 0.5);
77  pnh.param("clip_far", clip_far, 4.0);
78  clip_near_sq_ = clip_near * clip_near;
79  clip_far_sq_ = clip_far * clip_far;
80 
81  double clip_z_min, clip_z_max;
82  pnh.param("clip_z_min", clip_z_min, -2.0);
83  pnh.param("clip_z_max", clip_z_max, 2.0);
84  clip_z_min_ = clip_z_min;
85  clip_z_max_ = clip_z_max;
86 
87  double beam_likelihood_min;
88  pnh.param("beam_likelihood", beam_likelihood_min, 0.2);
89  beam_likelihood_min_ = beam_likelihood_min;
90  beam_likelihood_ = std::pow(beam_likelihood_min, 1.0 / static_cast<float>(num_points));
91 
92  double ang_total_ref;
93  pnh.param("ang_total_ref", ang_total_ref, M_PI / 6.0);
94  sin_total_ref_ = sinf(ang_total_ref);
95 
96  int filter_label_max;
97  pnh.param("filter_label_max", filter_label_max, static_cast<int>(0xFFFFFFFF));
98  filter_label_max_ = filter_label_max;
99 
100  pnh.param("add_penalty_short_only_mode", add_penalty_short_only_mode_, true);
101  double hit_range;
102  pnh.param("hit_range", hit_range, 0.3);
103  hit_range_sq_ = std::pow(hit_range, 2);
104  bool use_raycast_using_dda;
105  pnh.param("use_raycast_using_dda", use_raycast_using_dda, false);
106  if (use_raycast_using_dda)
107  {
108  double ray_angle_half;
109  pnh.param("ray_angle_half", ray_angle_half, 0.25 * M_PI / 180.0);
110  double dda_grid_size;
111  pnh.param("dda_grid_size", dda_grid_size, 0.2);
112  const double grid_size_max = std::max({ map_grid_x_, map_grid_y_, map_grid_z_ }); // NOLINT(whitespace/braces)
113  if (dda_grid_size < grid_size_max)
114  {
115  ROS_WARN("dda_grid_size must be larger than grid size. New value: %f", grid_size_max);
116  dda_grid_size = grid_size_max;
117  }
118 
119  raycaster_ = std::make_shared<RaycastUsingDDA<PointType>>(
120  map_grid_x_, map_grid_y_, map_grid_z_, dda_grid_size, ray_angle_half, hit_range);
121  }
122  else
123  {
124  raycaster_ = std::make_shared<RaycastUsingKDTree<PointType>>(
125  map_grid_x_, map_grid_y_, map_grid_z_, hit_range);
126  }
127 }
128 
130  const size_t num_particles,
131  const size_t current_num_particles)
132 {
133  if (current_num_particles <= num_particles)
134  {
136  return;
137  }
138  size_t num = num_points_default_ * num_particles / current_num_particles;
139  if (num < num_points_global_)
140  num = num_points_global_;
141 
142  num_points_ = num;
143 }
144 
145 typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr
147  const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc) const
148 {
149  const auto local_points_filter = [this](const LidarMeasurementModelBase::PointType& p)
150  {
151  if (p.x * p.x + p.y * p.y > clip_far_sq_)
152  return true;
153  if (p.x * p.x + p.y * p.y < clip_near_sq_)
154  return true;
155  if (p.z < clip_z_min_ || clip_z_max_ < p.z)
156  return true;
157  return false;
158  };
159  pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_filtered(
160  new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
161  *pc_filtered = *pc;
162  pc_filtered->erase(
163  std::remove_if(pc_filtered->begin(), pc_filtered->end(), local_points_filter), pc_filtered->end());
164  pc_filtered->width = 1;
165  pc_filtered->height = pc_filtered->points.size();
166 
167  return sampler_->sample(pc_filtered, num_points_);
168 }
169 
172  const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc,
173  const std::vector<Vec3>& origins,
174  const State6DOF& s) const
175 {
176  if (!pc)
177  return LidarMeasurementResult(1, 0);
178  if (pc->size() == 0)
179  return LidarMeasurementResult(1, 0);
180  pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_particle(
181  new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
182 
183  float score_beam = 1.0;
184  *pc_particle = *pc;
185  s.transform(*pc_particle);
186  for (auto& p : pc_particle->points)
187  {
188  const int beam_header_id = p.label;
190  const BeamStatus status =
191  getBeamStatus(kdtree, s.pos_ + s.rot_ * origins[beam_header_id], Vec3(p.x, p.y, p.z), point);
192  if ((status == BeamStatus::SHORT) || (!add_penalty_short_only_mode_ && (status == BeamStatus::LONG)))
193  {
194  score_beam *= beam_likelihood_;
195  }
196  }
197  if (score_beam < beam_likelihood_min_)
198  score_beam = beam_likelihood_min_;
199 
200  return LidarMeasurementResult(score_beam, 1.0);
201 }
202 
205  const Vec3& lidar_pos,
206  const Vec3& scan_pos,
207  typename mcl_3dl::Raycast<PointType>::CastResult& result) const
208 {
209  raycaster_->setRay(kdtree, lidar_pos, scan_pos);
210  while (raycaster_->getNextCastResult(result))
211  {
212  if (!result.collision_)
213  continue;
214  if (result.point_->label > filter_label_max_)
215  continue;
216  // reject total reflection
217  if (result.sin_angle_ > sin_total_ref_)
218  {
219  const float distance_from_point_sq = std::pow(scan_pos[0] - result.point_->x, 2) +
220  std::pow(scan_pos[1] - result.point_->y, 2) +
221  std::pow(scan_pos[2] - result.point_->z, 2);
222 
223  if (distance_from_point_sq < hit_range_sq_)
224  {
225  return BeamStatus::HIT;
226  }
227  else
228  {
229  return BeamStatus::SHORT;
230  }
231  }
232  else
233  {
235  }
236  }
237  return BeamStatus::LONG;
238 }
239 
240 } // namespace mcl_3dl
void transform(pcl::PointCloud< PointType > &pc) const
Definition: state_6dof.h:188
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
std::shared_ptr< ChunkedKdtree > Ptr
mcl_3dl::Vec3 pos_
Definition: state_6dof.h:52
std::shared_ptr< Raycast< LidarMeasurementModelBase::PointType > > raycaster_
const POINT_TYPE * point_
Definition: raycast.h:51
#define ROS_WARN(...)
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
BeamStatus getBeamStatus(ChunkedKdtree< PointType >::Ptr &kdtree, const Vec3 &beam_begin, const Vec3 &beam_end, typename mcl_3dl::Raycast< PointType >::CastResult &result) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
mcl_3dl::Quat rot_
Definition: state_6dof.h:53
void setGlobalLocalizationStatus(const size_t num_particles, const size_t current_num_particles)
void loadConfig(const ros::NodeHandle &nh, const std::string &name)
LidarMeasurementModelBeam(const float grid_size_x, const float grid_size_y, const float grid_size_z)


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