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 <sensor_msgs/LaserScan.h>
00010 #include <boost/optional.hpp>
00011 #include <string>
00012
00013 namespace occupancy_grid_utils
00014 {
00015
00016
00017
00018
00019
00020 typedef std::pair<RayTraceIterator, RayTraceIterator> RayTraceIterRange;
00021
00034 RayTraceIterRange rayTrace (const nav_msgs::MapMetaData& info, const geometry_msgs::Point& p1,
00035 const geometry_msgs::Point& p2, bool project_target_onto_grid=false,
00036 bool project_source_onto_grid=false);
00037
00038
00039
00040
00041
00042
00052 sensor_msgs::LaserScan::Ptr
00053 simulateRangeScan (const nav_msgs::OccupancyGrid& grid, const geometry_msgs::Pose& sensor_pose,
00054 const sensor_msgs::LaserScan& scanner_info,
00055 bool unknown_cells_are_obstacles=false);
00056
00057
00058
00059
00060
00061
00063 const double DEFAULT_OCCUPANCY_THRESHOLD=0.1;
00064
00066 const double DEFAULT_MAX_DISTANCE=10.0;
00067
00069 const double DEFAULT_MIN_PASS_THROUGH=2;
00070
00083 OverlayClouds createCloudOverlay (const nav_msgs::OccupancyGrid& grid, const std::string& frame_id,
00084 double occupancy_threshold=DEFAULT_OCCUPANCY_THRESHOLD,
00085 double max_distance=DEFAULT_MAX_DISTANCE,
00086 double min_pass_through=DEFAULT_MIN_PASS_THROUGH);
00087
00088
00090 void addCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud);
00091
00094 void removeCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud);
00095
00097 void addKnownFreePoint (OverlayClouds* overlay, const geometry_msgs::Point& p,
00098 double r);
00099
00100
00102 nav_msgs::OccupancyGrid::Ptr getGrid (const OverlayClouds& overlay);
00103
00104
00105 void resetCounts (OverlayClouds* overlay);
00106
00107
00108 nav_msgs::MapMetaData gridInfo (const OverlayClouds& overlay);
00109
00110
00111 }
00112
00113 #endif // include guard