ray_tracer.h
Go to the documentation of this file.
00001 #ifndef OCCUPANCY_GRID_UTILS_RAY_TRACER_H
00002 #define OCCUPANCY_GRID_UTILS_RAY_TRACER_H
00003 
00004 #include <occupancy_grid_utils/impl/ray_trace_iterator.h>
00005 #include <occupancy_grid_utils/LocalizedCloud.h>
00006 #include <occupancy_grid_utils/OverlayClouds.h>
00007 #include <nav_msgs/OccupancyGrid.h>
00008 #include <geometry_msgs/Pose.h>
00009 #include <boost/optional.hpp>
00010 #include <string>
00011 
00012 namespace occupancy_grid_utils
00013 {
00014 
00015 /************************************************************
00016  * Basic ray tracing
00017  ************************************************************/
00018 
00019 typedef std::pair<RayTraceIterator, RayTraceIterator> RayTraceIterRange;
00020 
00033 RayTraceIterRange rayTrace (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p1, 
00034                             const geometry_msgs::Point& p2, bool project_target_onto_grid=false,
00035                             bool project_source_onto_grid=false);
00036 
00037 
00038 /************************************************************
00039  * Overlaying point clouds
00040  ************************************************************/
00041 
00042 
00044 const double DEFAULT_OCCUPANCY_THRESHOLD=0.1;
00045 
00047 const double DEFAULT_MAX_DISTANCE=10.0;
00048 
00050 const double DEFAULT_MIN_PASS_THROUGH=2;
00051 
00063 OverlayClouds createCloudOverlay (const nav_msgs::MapMetaData& geometry, const std::string& frame_id,
00064                                   double occupancy_threshold=DEFAULT_OCCUPANCY_THRESHOLD,
00065                                   double max_distance=DEFAULT_MAX_DISTANCE,
00066                                   double min_pass_through=DEFAULT_MIN_PASS_THROUGH);
00067 
00069 void addCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud);
00070 
00073 void removeCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud);
00074 
00075 
00077 nav_msgs::OccupancyGrid::Ptr getGrid (const OverlayClouds& overlay);
00078 
00079 // \brief Reset all counts to initial state in \a overlay
00080 void resetCounts (OverlayClouds* overlay);
00081 
00082 // \brief Get the occupancy grid dimensions.
00083 nav_msgs::MapMetaData gridInfo (const OverlayClouds& overlay);
00084   
00085 
00086 } // namespace occupancy_grid_utils
00087 
00088 #endif // include guard


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