38 #include <pcl/point_types.h>
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)
64 const std::string& name)
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);
74 double clip_near, clip_far;
75 pnh.
param(
"clip_near", clip_near, 0.5);
76 pnh.
param(
"clip_far", clip_far, 4.0);
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);
86 double beam_likelihood_min;
87 pnh.
param(
"beam_likelihood", beam_likelihood_min, 0.2);
89 beam_likelihood_ = std::pow(beam_likelihood_min, 1.0 /
static_cast<float>(num_points));
92 pnh.
param(
"ang_total_ref", ang_total_ref, M_PI / 6.0);
96 pnh.
param(
"filter_label_max", filter_label_max,
static_cast<int>(0xFFFFFFFF));
101 pnh.
param(
"hit_range", hit_range, 0.3);
103 bool use_raycast_using_dda;
104 pnh.
param(
"use_raycast_using_dda", use_raycast_using_dda,
false);
105 if (use_raycast_using_dda)
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);
112 if (dda_grid_size < grid_size_max)
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;
118 raycaster_ = std::make_shared<RaycastUsingDDA<PointType>>(
123 raycaster_ = std::make_shared<RaycastUsingKDTree<PointType>>(
129 const size_t num_particles,
130 const size_t current_num_particles)
132 if (current_num_particles <= num_particles)
144 typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr
146 const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc)
const
158 pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_filtered(
159 new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
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();
171 const typename pcl::PointCloud<LidarMeasurementModelBase::PointType>::ConstPtr& pc,
172 const std::vector<Vec3>& origins,
179 pcl::PointCloud<LidarMeasurementModelBase::PointType>::Ptr pc_particle(
180 new pcl::PointCloud<LidarMeasurementModelBase::PointType>);
182 float score_beam = 1.0;
184 s.transform(*pc_particle);
185 for (
auto& p : pc_particle->points)
187 const int beam_header_id = p.label;
190 getBeamStatus(kdtree,
s.pos_ +
s.rot_ * origins[beam_header_id],
Vec3(p.x, p.y, p.z), point);
204 const Vec3& lidar_pos,
205 const Vec3& scan_pos,
208 raycaster_->setRay(kdtree, lidar_pos, scan_pos);
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);