lidar_measurement_model_likelihood.h
Go to the documentation of this file.
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_LIKELIHOOD_H
00031 #define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_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 LidarMeasurementModelLikelihood : 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 match_weight_;
00060   float match_dist_min_;
00061   float match_dist_flat_;
00062 
00063   PointCloudRandomSampler sampler_;
00064 
00065 public:
00066   inline float getMaxSearchRange() const
00067   {
00068     return match_dist_min_;
00069   }
00070 
00071   void loadConfig(
00072       const ros::NodeHandle& nh,
00073       const std::string& name);
00074   void setGlobalLocalizationStatus(
00075       const size_t num_particles,
00076       const size_t current_num_particles);
00077   pcl::PointCloud<PointType>::Ptr filter(
00078       const pcl::PointCloud<PointType>::ConstPtr& pc) const;
00079   LidarMeasurementResult measure(
00080       ChunkedKdtree<PointType>::Ptr& kdtree,
00081       const pcl::PointCloud<PointType>::ConstPtr& pc,
00082       const std::vector<Vec3>& origins,
00083       const State6DOF& s) const;
00084 };
00085 }  // namespace mcl_3dl
00086 
00087 #endif  // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_LIKELIHOOD_H


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 20 2019 20:04:43