ray_tracer.cpp
Go to the documentation of this file.
00001 #include <occupancy_grid_utils/ray_tracer.h>
00002 #include <occupancy_grid_utils/exceptions.h>
00003 #include <boost/bind.hpp>
00004 #include <boost/ref.hpp>
00005 #include <boost/optional.hpp>
00006 #include <algorithm>
00007 #include <ros/assert.h>
00008 
00009 namespace occupancy_grid_utils
00010 {
00011 
00012 namespace nm=nav_msgs;
00013 namespace gm=geometry_msgs;
00014 
00015 using boost::bind;
00016 using boost::ref;
00017 using boost::optional;
00018 
00019 RayTraceIterRange rayTrace (const Cell& c1, const Cell& c2)
00020 {
00021   return RayTraceIterRange(RayTraceIterator(c1,c2), RayTraceIterator(c2,c2,true));
00022 }
00023 
00024 inline
00025 bool cellWithinBounds (const nm::MapMetaData& info, const Cell& c)
00026 {
00027   return withinBounds(info, c);
00028 }
00029 
00030 optional<Cell> rayTraceOntoGrid (const nm::MapMetaData& info, const Cell& c1, const Cell& c2)
00031 {
00032   RayTraceIterRange r = rayTrace(c2, c1);
00033   RayTraceIterator pos = std::find_if (r.first, r.second, bind(cellWithinBounds, ref(info), _1));
00034   optional<Cell> c;
00035   if (pos!=r.second)
00036     c = *pos;
00037   return c;
00038 }
00039 
00040 RayTraceIterRange rayTrace (const nm::MapMetaData& info, const gm::Point& p1, const gm::Point& p2,
00041                             bool project_onto_grid, bool project_source_onto_grid)
00042 {
00043   Cell c1 = pointCell(info, p1);
00044   Cell c2 = pointCell(info, p2);
00045   ROS_DEBUG_STREAM_NAMED ("ray_trace", "Ray tracing between " << c1.x <<
00046                           ", " << c1.y << " and " << c2.x << ", " << c2.y);
00047   const RayTraceIterator done(c1, c1, true);
00048   const RayTraceIterRange empty_range(done, done);
00049   if (!withinBounds(info, c1)) {
00050     if (project_source_onto_grid) {
00051       const optional<Cell> c = rayTraceOntoGrid(info, c2, c1);
00052       if (c)
00053         c1 = *c;
00054       else
00055         return empty_range;
00056     }
00057     else
00058       throw PointOutOfBoundsException(p1);
00059   }
00060   
00061   if (!withinBounds(info, p2)) {
00062     if (project_onto_grid) {
00063       const optional<Cell> c = rayTraceOntoGrid(info, c1, c2);
00064       if (c)
00065         c2 = *c;
00066       else
00067         return empty_range;
00068     }
00069     else {
00070       throw PointOutOfBoundsException(p2);
00071     }
00072   }
00073 
00074   ROS_DEBUG_STREAM_NAMED ("ray_trace", "Projected ray trace endpoints to " << c1.x <<
00075                           ", " << c1.y << " and " << c2.x << ", " << c2.y);
00076   return rayTrace(c1, c2);
00077 }
00078 
00079 
00080 
00081 
00082 
00083 } // namespace occupancy_grid_utils


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:09