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


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04