lidar_measurement_model_base.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_MODEL_BASE_H
31 #define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
32 
33 #include <string>
34 #include <utility>
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>
43 #include <mcl_3dl/point_types.h>
44 #include <mcl_3dl/state_6dof.h>
45 #include <mcl_3dl/vec3.h>
46 
47 namespace mcl_3dl
48 {
50 {
51  float likelihood;
52  float quality;
53 
54  LidarMeasurementResult(const float likelihood_value, const float quality_value)
55  : likelihood(likelihood_value)
56  , quality(quality_value)
57  {
58  }
59 };
60 
62 {
63 public:
64  using Ptr = std::shared_ptr<LidarMeasurementModelBase>;
66 
67  virtual void loadConfig(
68  const ros::NodeHandle& nh,
69  const std::string& name) = 0;
70  virtual void setGlobalLocalizationStatus(
71  const size_t, const size_t) = 0;
72  virtual float getMaxSearchRange() const = 0;
73 
74  virtual pcl::PointCloud<PointType>::Ptr filter(
75  const pcl::PointCloud<PointType>::ConstPtr&) const = 0;
76 
77  virtual LidarMeasurementResult measure(
79  const pcl::PointCloud<PointType>::ConstPtr&,
80  const std::vector<Vec3>&,
81  const State6DOF&) const = 0;
82 };
83 } // namespace mcl_3dl
84 
85 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
std::shared_ptr< ChunkedKdtree > Ptr
std::shared_ptr< LidarMeasurementModelBase > Ptr
LidarMeasurementResult(const float likelihood_value, const float quality_value)


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