00001 /* 00002 * Copyright (c) 2018, the mcl_3dl authors 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the copyright holder nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #ifndef MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H 00031 #define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H 00032 00033 #include <string> 00034 #include <utility> 00035 #include <vector> 00036 00037 #include <ros/ros.h> 00038 00039 #include <pcl/point_types.h> 00040 #include <pcl_ros/point_cloud.h> 00041 00042 #include <mcl_3dl/chunked_kdtree.h> 00043 #include <mcl_3dl/point_types.h> 00044 #include <mcl_3dl/state_6dof.h> 00045 #include <mcl_3dl/vec3.h> 00046 00047 namespace mcl_3dl 00048 { 00049 struct LidarMeasurementResult 00050 { 00051 float likelihood; 00052 float quality; 00053 00054 LidarMeasurementResult(const float likelihood_value, const float quality_value) 00055 : likelihood(likelihood_value) 00056 , quality(quality_value) 00057 { 00058 } 00059 }; 00060 00061 class LidarMeasurementModelBase 00062 { 00063 public: 00064 using Ptr = std::shared_ptr<LidarMeasurementModelBase>; 00065 using PointType = mcl_3dl::PointXYZIL; 00066 00067 virtual void loadConfig( 00068 const ros::NodeHandle& nh, 00069 const std::string& name) = 0; 00070 virtual void setGlobalLocalizationStatus( 00071 const size_t, const size_t) = 0; 00072 virtual float getMaxSearchRange() const = 0; 00073 00074 virtual pcl::PointCloud<PointType>::Ptr filter( 00075 const pcl::PointCloud<PointType>::ConstPtr&) const = 0; 00076 00077 virtual LidarMeasurementResult measure( 00078 ChunkedKdtree<PointType>::Ptr&, 00079 const pcl::PointCloud<PointType>::ConstPtr&, 00080 const std::vector<Vec3>&, 00081 const State6DOF&) const = 0; 00082 }; 00083 } // namespace mcl_3dl 00084 00085 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H