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 PROVIDEDNode 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_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 00031 #define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 00032 00033 #include <string> 00034 #include <vector> 00035 00036 #include <ros/ros.h> 00037 00038 #include <pcl/point_types.h> 00039 #include <pcl_ros/point_cloud.h> 00040 00041 #include <mcl_3dl/chunked_kdtree.h> 00042 #include <mcl_3dl/lidar_measurement_model_base.h> 00043 #include <mcl_3dl/pf.h> 00044 #include <mcl_3dl/point_cloud_random_sampler.h> 00045 #include <mcl_3dl/vec3.h> 00046 00047 namespace mcl_3dl 00048 { 00049 class LidarMeasurementModelBeam : public LidarMeasurementModelBase 00050 { 00051 private: 00052 size_t num_points_; 00053 size_t num_points_default_; 00054 size_t num_points_global_; 00055 float clip_far_sq_; 00056 float clip_near_sq_; 00057 float clip_z_min_; 00058 float clip_z_max_; 00059 float beam_likelihood_min_; 00060 float beam_likelihood_; 00061 float sin_total_ref_; 00062 float map_grid_min_; 00063 float map_grid_max_; 00064 00065 PointCloudRandomSampler sampler_; 00066 00067 public: 00068 LidarMeasurementModelBeam(const float x, const float y, const float z); 00069 00070 inline float getMaxSearchRange() const 00071 { 00072 return map_grid_max_ * 4; 00073 } 00074 inline float getSinTotalRef() const 00075 { 00076 return sin_total_ref_; 00077 } 00078 00079 void loadConfig( 00080 const ros::NodeHandle& nh, 00081 const std::string& name); 00082 void setGlobalLocalizationStatus( 00083 const size_t num_particles, 00084 const size_t current_num_particles); 00085 pcl::PointCloud<PointType>::Ptr filter( 00086 const pcl::PointCloud<PointType>::ConstPtr& pc) const; 00087 LidarMeasurementResult measure( 00088 ChunkedKdtree<PointType>::Ptr& kdtree, 00089 const pcl::PointCloud<PointType>::ConstPtr& pc, 00090 const std::vector<Vec3>& origins, 00091 const State6DOF& s) const; 00092 }; 00093 } // namespace mcl_3dl 00094 00095 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H