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 PROVIDEDNode 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 <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/chunked_kdtree.h>
43 #include <mcl_3dl/pf.h>
45 #include <mcl_3dl/vec3.h>
46 
47 namespace mcl_3dl
48 {
50 {
51 private:
52  size_t num_points_;
55  float clip_far_sq_;
57  float clip_z_min_;
58  float clip_z_max_;
64 
66 
67 public:
68  LidarMeasurementModelBeam(const float x, const float y, const float z);
69 
70  inline float getMaxSearchRange() const
71  {
72  return map_grid_max_ * 4;
73  }
74  inline float getSinTotalRef() const
75  {
76  return sin_total_ref_;
77  }
78 
79  void loadConfig(
80  const ros::NodeHandle& nh,
81  const std::string& name);
83  const size_t num_particles,
84  const size_t current_num_particles);
85  pcl::PointCloud<PointType>::Ptr filter(
86  const pcl::PointCloud<PointType>::ConstPtr& pc) const;
89  const pcl::PointCloud<PointType>::ConstPtr& pc,
90  const std::vector<Vec3>& origins,
91  const State6DOF& s) const;
92 };
93 } // namespace mcl_3dl
94 
95 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
XmlRpcServer s
std::shared_ptr< ChunkedKdtree > Ptr
LidarMeasurementModelBeam(const float x, const float y, const float z)
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
void setGlobalLocalizationStatus(const size_t num_particles, const size_t current_num_particles)
void loadConfig(const ros::NodeHandle &nh, const std::string &name)


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36