localization_monitor.cpp
Go to the documentation of this file.
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 #include <flirtlib_ros/localization_monitor.h>
00040 
00041 namespace flirtlib_ros
00042 {
00043 
00044 namespace sm=sensor_msgs;
00045 namespace gm=geometry_msgs;
00046 namespace gu=occupancy_grid_utils;
00047 namespace nm=nav_msgs;
00048 
00049 ScanPoseEvaluator::ScanPoseEvaluator (const nm::OccupancyGrid& g,
00050                                       const double threshold) :
00051   geom_(g.info), distances_(gu::distanceField(g, threshold))
00052 {
00053   ROS_INFO ("Scan pose evaluator initialized");
00054 }
00055 
00056 gm::Pose ScanPoseEvaluator::adjustPose (const sm::LaserScan& scan,
00057                                         const gm::Pose& initial_pose,
00058                                         const double pos_range,
00059                                         const double dpos,
00060                                         const double dtheta) const
00061 {
00062   const double x0=initial_pose.position.x;
00063   const double y0=initial_pose.position.y;
00064   const double theta0 = tf::getYaw(initial_pose.orientation);
00065   
00066   double best = 1e9;
00067   gm::Pose best_pose;
00068 
00069   for (double x=x0-pos_range; x<x0+pos_range; x+=dpos)
00070   {
00071     for (double y=y0-pos_range; y<y0+pos_range; y+=dpos)
00072     {
00073       for (double th=theta0-3.14; th<theta0+3.14; th+=dtheta)
00074       {
00075         gm::Pose p;
00076         p.position.x = x;
00077         p.position.y = y;
00078         p.orientation = tf::createQuaternionMsgFromYaw(th);
00079         double badness = (*this)(scan, p);
00080         if (badness < best)
00081         {
00082           ROS_DEBUG_NAMED ("adjust_pose", "Badness of %.2f, %.2f, %.2f is %.2f",
00083                            x, y, th, badness);
00084           best = badness;
00085           best_pose = p;
00086         }
00087       }
00088     }
00089   }
00090   
00091   ROS_ASSERT(best<1e8);
00092   return best_pose;
00093 }
00094 
00095 float ScanPoseEvaluator::operator() (const sm::LaserScan& scan,
00096                                      const gm::Pose& pose) const
00097 {
00098   // Scanner pose
00099   const double theta0 = tf::getYaw(pose.orientation);
00100   const double x0 = pose.position.x;
00101   const double y0 = pose.position.y;
00102 
00103   std::vector<double> distances;
00104 
00105   // Iterate over range readings, and get the coordinates of the 
00106   // corresponding point in the map frame for the given sensor pose
00107   for (size_t i=0; i<scan.ranges.size(); i++)
00108   {
00109     const double theta = theta0 + scan.angle_min + i*scan.angle_increment;
00110     const double r = scan.ranges[i];
00111     gm::Point p;
00112     p.x = x0 + cos(theta)*r;
00113     p.y = y0 + sin(theta)*r;
00114     p.z = 0;
00115     
00116     // Now figure out the distance to the closest obstacle in the map
00117     // If the point's off the map, use a large value (we're taking a median, 
00118     // so it doesn't matter)
00119     const gu::Cell c = gu::pointCell(geom_, p);
00120     const double d = withinBounds(geom_, c) ? distances_[c] : 1e9;
00121     distances.push_back(d);
00122   }
00123   
00124   // Return the median distance
00125   sort(distances.begin(), distances.end());
00126   const size_t mid = distances.size()/2;
00127   return distances[mid];
00128 }
00129 
00130 } // namespace


flirtlib_ros
Author(s): Bhaskara Marthi
autogenerated on Thu Nov 28 2013 11:21:50