lidar_measurement_model_beam.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_BEAM_H
31 #define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_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>
44 #include <mcl_3dl/pf.h>
46 #include <mcl_3dl/raycast.h>
47 #include <mcl_3dl/vec3.h>
48 
49 namespace mcl_3dl
50 {
52 {
53 private:
54  std::shared_ptr<Raycast<LidarMeasurementModelBase::PointType>> raycaster_;
55  size_t num_points_;
58  float clip_far_sq_;
60  float clip_z_min_;
61  float clip_z_max_;
65  float map_grid_x_;
66  float map_grid_y_;
67  float map_grid_z_;
73 
74 public:
75  enum class BeamStatus
76  {
77  SHORT,
78  HIT,
79  LONG,
81  };
82  LidarMeasurementModelBeam(const float grid_size_x, const float grid_size_y, const float grid_size_z);
83 
84  inline float getMaxSearchRange() const
85  {
86  return search_range_;
87  }
88  inline float getSinTotalRef() const
89  {
90  return sin_total_ref_;
91  }
92  inline uint32_t getFilterLabelMax() const
93  {
94  return filter_label_max_;
95  }
96  void loadConfig(
97  const ros::NodeHandle& nh,
98  const std::string& name);
100  const size_t num_particles,
101  const size_t current_num_particles);
102  pcl::PointCloud<PointType>::Ptr filter(
103  const pcl::PointCloud<PointType>::ConstPtr& pc) const;
106  const pcl::PointCloud<PointType>::ConstPtr& pc,
107  const std::vector<Vec3>& origins,
108  const State6DOF& s) const;
111  const Vec3& beam_begin, const Vec3& beam_end,
112  typename mcl_3dl::Raycast<PointType>::CastResult& result) const;
113 };
114 } // namespace mcl_3dl
115 
116 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H
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::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
ros.h
mcl_3dl::LidarMeasurementModelBeam::hit_range_sq_
float hit_range_sq_
Definition: lidar_measurement_model_beam.h:71
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
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
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::LidarMeasurementModelBeam::beam_likelihood_
float beam_likelihood_
Definition: lidar_measurement_model_beam.h:63
mcl_3dl::LidarMeasurementModelBase
Definition: lidar_measurement_model_base.h:64
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
lidar_measurement_model_base.h
mcl_3dl::LidarMeasurementModelBeam::additional_search_range_
float additional_search_range_
Definition: lidar_measurement_model_beam.h:70
mcl_3dl::LidarMeasurementModelBeam::getFilterLabelMax
uint32_t getFilterLabelMax() const
Definition: lidar_measurement_model_beam.h:92
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::getSinTotalRef
float getSinTotalRef() const
Definition: lidar_measurement_model_beam.h:88
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
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::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
chunked_kdtree.h
mcl_3dl::LidarMeasurementModelBeam::getMaxSearchRange
float getMaxSearchRange() const
Definition: lidar_measurement_model_beam.h:84
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
Definition: lidar_measurement_model_beam.h:51
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