00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00038 #include <occupancy_grid_utils/ray_tracer.h>
00039 #include <ros/assert.h>
00040 #include <tf/transform_datatypes.h>
00041 #include <boost/foreach.hpp>
00042 #include <boost/bind.hpp>
00043 #include <boost/ref.hpp>
00044 #include <boost/optional.hpp>
00045
00046 namespace occupancy_grid_utils
00047 {
00048
00049 namespace gm=geometry_msgs;
00050 namespace nm=nav_msgs;
00051
00052 using boost::bind;
00053 using boost::ref;
00054 using std::vector;
00055
00056 typedef boost::shared_ptr<nm::OccupancyGrid> GridPtr;
00057 typedef boost::shared_ptr<nm::OccupancyGrid const> GridConstPtr;
00058
00059
00060 inline gm::Point transformPt (const btTransform& trans, const gm::Point32& p)
00061 {
00062 const btVector3 pt(p.x, p.y, p.z);
00063 gm::Point transformed;
00064 tf::pointTFToMsg(trans*pt, transformed);
00065 return transformed;
00066 }
00067
00068 inline double euclideanDistance (const gm::Point& p1, const gm::Point& p2)
00069 {
00070 const double dx=p1.x-p2.x;
00071 const double dy=p1.y-p2.y;
00072 const double dz=p1.z-p2.z;
00073 return sqrt(dx*dx + dy*dy + dz*dz);
00074 }
00075
00076
00077
00078 inline int8_t determineOccupancy (const unsigned hit_count, const unsigned pass_through_count,
00079 const double occupancy_threshold, const double min_pass_through)
00080 {
00081 int8_t ret;
00082 if (pass_through_count < min_pass_through)
00083 ret=UNKNOWN;
00084 else if (hit_count > pass_through_count*occupancy_threshold)
00085 ret=OCCUPIED;
00086 else
00087 ret=UNOCCUPIED;
00088 ROS_DEBUG_NAMED ("overlay_get_grid", " Hit count is %u, pass through count is %u, occupancy is %d",
00089 hit_count, pass_through_count, ret);
00090 return ret;
00091 }
00092
00093 OverlayClouds createCloudOverlay (const nm::OccupancyGrid& grid, const std::string& frame_id,
00094 double occupancy_threshold,
00095 double max_distance, double min_pass_through)
00096 {
00097 OverlayClouds overlay;
00098 overlay.grid = grid;
00099 overlay.frame_id = frame_id;
00100 overlay.occupancy_threshold = occupancy_threshold;
00101 overlay.max_distance = max_distance;
00102 overlay.min_pass_through = min_pass_through;
00103 overlay.hit_counts.resize(grid.info.height*grid.info.width);
00104 overlay.pass_through_counts.resize(grid.info.height*grid.info.width);
00105 ROS_ASSERT(min_pass_through > 0);
00106 return overlay;
00107 }
00108
00109 void addKnownFreePoint (OverlayClouds* overlay, const gm::Point& p, const double r)
00110 {
00111 const nm::MapMetaData& geom = overlay->grid.info;
00112 const int cell_radius = floor(r/geom.resolution);
00113 const Cell c = pointCell(geom, p);
00114 for (int x= c.x-cell_radius; x<=c.x+cell_radius; x++)
00115 {
00116 for (int y=c.y-cell_radius; y<=c.y+cell_radius; y++)
00117 {
00118 const Cell c2(x, y);
00119 if (withinBounds(geom, c2))
00120 {
00121 const index_t ind = cellIndex(geom, c2);
00122 overlay->hit_counts[ind] = 0;
00123 overlay->pass_through_counts[ind] = overlay->min_pass_through+1;
00124 }
00125 }
00126 }
00127 }
00128
00129
00130 void addCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud, const int inc)
00131 {
00132
00133 ROS_ASSERT_MSG(overlay->frame_id==cloud->header.frame_id,
00134 "Frame id %s of overlayed cloud didn't match existing one %s",
00135 cloud->header.frame_id.c_str(), overlay->frame_id.c_str());
00136 const index_t num_cells = overlay->grid.info.width*overlay->grid.info.height;
00137 ROS_ASSERT(num_cells>0);
00138
00139 const gm::Point& sensor_pos = cloud->sensor_pose.position;
00140 ROS_DEBUG_NAMED ("overlay", "Ray tracing from %.2f, %.2f", sensor_pos.x, sensor_pos.y);
00141
00142
00143 btTransform sensor_to_world;
00144 tf::poseMsgToTF(cloud->sensor_pose, sensor_to_world);
00145 vector<gm::Point> transformed_points(cloud->cloud.points.size());
00146 transform(cloud->cloud.points.begin(), cloud->cloud.points.end(), transformed_points.begin(),
00147 bind(transformPt, ref(sensor_to_world), _1));
00148
00149
00150 BOOST_FOREACH (const gm::Point& p, transformed_points) {
00151
00152
00153 if (euclideanDistance(sensor_pos, p) < overlay->max_distance) {
00154 ROS_DEBUG_NAMED ("overlay_counts", " Ray tracing to point %.2f, %.2f", p.x, p.y);
00155 boost::optional<index_t> last_ind;
00156
00157 const bool have_existing_grid = !overlay->grid.data.empty();
00158
00159
00160
00161 BOOST_FOREACH (const Cell& c, rayTrace(overlay->grid.info, sensor_pos, p, true, true)) {
00162 last_ind = cellIndex(overlay->grid.info, c);
00163 overlay->pass_through_counts[*last_ind] += inc;
00164 if (have_existing_grid && overlay->grid.data[*last_ind] == OCCUPIED)
00165 break;
00166 ROS_ASSERT(overlay->pass_through_counts[*last_ind]>=0);
00167 ROS_DEBUG_NAMED ("overlay_counts", " Pass-through counts for %d, %d are now %u", c.x, c.y,
00168 overlay->pass_through_counts[*last_ind]);
00169 }
00170
00171 if (last_ind) {
00172
00173 const Cell last_cell = indexCell(overlay->grid.info, *last_ind);
00174 if (last_cell == pointCell(overlay->grid.info, p)) {
00175 overlay->hit_counts[*last_ind] += inc;
00176 ROS_ASSERT(overlay->hit_counts[*last_ind]>=0);
00177 ROS_DEBUG_NAMED ("overlay_counts", " Hit counts for %d, %d are now %u", last_cell.x, last_cell.y,
00178 overlay->hit_counts[*last_ind]);
00179 }
00180 }
00181 }
00182 }
00183 ROS_DEBUG_NAMED ("overlay", "Done ray tracing from %.2f, %.2f", sensor_pos.x, sensor_pos.y);
00184 }
00185
00186
00187 void addCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud)
00188 {
00189 addCloud(overlay, cloud, 1);
00190 }
00191
00192 void removeCloud (OverlayClouds* overlay, LocalizedCloud::ConstPtr cloud)
00193 {
00194 addCloud(overlay, cloud, -1);
00195 }
00196
00197
00198
00199 GridPtr getGrid (const OverlayClouds& overlay)
00200 {
00201 GridPtr grid(new nm::OccupancyGrid());
00202 grid->info = overlay.grid.info;
00203 grid->header.frame_id = overlay.frame_id;
00204 ROS_DEBUG_STREAM_NAMED ("overlay_get_grid", "Getting overlaid grid with geometry " << overlay.grid.info);
00205 grid->data.resize(overlay.grid.info.width*overlay.grid.info.height);
00206 transform(overlay.hit_counts.begin(), overlay.hit_counts.end(), overlay.pass_through_counts.begin(),
00207 grid->data.begin(), bind(determineOccupancy, _1, _2, overlay.occupancy_threshold,
00208 overlay.min_pass_through));
00209 return grid;
00210 }
00211
00212 void resetCounts (OverlayClouds* overlay)
00213 {
00214 fill(overlay->hit_counts.begin(), overlay->hit_counts.end(), 0);
00215 fill(overlay->pass_through_counts.begin(), overlay->pass_through_counts.end(), 0);
00216 }
00217
00218 nm::MapMetaData gridInfo (const OverlayClouds& overlay)
00219 {
00220 return overlay.grid.info;
00221 }
00222
00223 }