00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 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 Willow Garage, Inc. 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 00039 #ifndef FLIRTLIB_ROS_LOCALIZATION_MONITOR_H 00040 #define FLIRTLIB_ROS_LOCALIZATION_MONITOR_H 00041 00042 #include <occupancy_grid_utils/geometry.h> 00043 #include <sensor_msgs/LaserScan.h> 00044 #include <geometry_msgs/Pose.h> 00045 00046 namespace flirtlib_ros 00047 { 00048 00049 class ScanPoseEvaluator 00050 { 00051 public: 00052 00053 ScanPoseEvaluator (const nav_msgs::OccupancyGrid& g, 00054 double threshold); 00055 00056 // Return median distance (m) from each scan point to nearest obstacle 00057 float operator() (const sensor_msgs::LaserScan& scan, 00058 const geometry_msgs::Pose& pose) const; 00059 00060 // Locally adjust pose to improve quality 00061 geometry_msgs::Pose adjustPose (const sensor_msgs::LaserScan& scan, 00062 const geometry_msgs::Pose& init_pose, 00063 double pos_range, double dpos, 00064 double dtheta) const; 00065 00066 private: 00067 00068 nav_msgs::MapMetaData geom_; 00069 occupancy_grid_utils::DistanceField distances_; 00070 00071 }; 00072 00073 00074 } // namespace 00075 00076 #endif // include guard