00001 #include "pointmatcher_ros/get_params_from_server.h"
00002 #include "ethzasl_gridmap_2d/grid-map.h"
00003 #include "ethzasl_gridmap_2d/grid-functors.h"
00004 #include "tf/transform_listener.h"
00005 #include "sensor_msgs/LaserScan.h"
00006
00007 using namespace std;
00008
00009 struct OccupancyGridBuilder
00010 {
00011 ros::NodeHandle nh;
00012 tf::TransformListener tfListener;
00013 std::string mapFrame;
00014 const float maxRange;
00015 const int obsVal;
00016 const int freeVal;
00017 const float invalidDist;
00018 GridMap::Group mapGroup;
00019 GridMap probMap;
00020 GridMap knownMap;
00021 ros::Publisher mapPub;
00022 ros::Subscriber laserScanSub;
00023
00024 OccupancyGridBuilder() :
00025 mapFrame(getParam<string>("map_frame", "map")),
00026 maxRange(getParam<double>("max_range", 80.)),
00027 obsVal(getParam<int>("obs_value", 8000)),
00028 freeVal(getParam<int>("free_value", -8000)),
00029
00030 invalidDist(getParam<double>("invalid_distance", 1.)),
00031 probMap(getParam<double>("resolution", 0.05), 0, &mapGroup),
00032 knownMap(&mapGroup, -1),
00033 mapPub(nh.advertise<nav_msgs::OccupancyGrid>("map", 2, true)),
00034 laserScanSub(nh.subscribe("scan", 10, &OccupancyGridBuilder::scanReceived, this))
00035 {
00036 }
00037
00038 void scanReceived(const sensor_msgs::LaserScan& scan)
00039 {
00040 typedef GridMap::Vector Vector;
00041 MapConstUpdater probUpdater(probMap, freeVal);
00042 Drawer knownUpdater(knownMap);
00043
00044 const ros::Time stamp(scan.header.stamp);
00045 tf::StampedTransform transform;
00046 assert(scan.ranges.size());
00047 float angle(scan.angle_min);
00048 for (size_t a = 0; a < scan.ranges.size(); ++a)
00049 {
00050 const float range(scan.ranges[a]);
00051 float end = -1;
00052 if (range >= scan.range_min && range <= scan.range_max)
00053 end = range;
00054 else if (invalidDist > 0)
00055 end = invalidDist;
00056 if (end != -1)
00057 {
00058 const ros::Time scanStamp(stamp + ros::Duration(scan.time_increment)*a);
00059
00060 tfListener.waitForTransform(mapFrame, scan.header.frame_id, scanStamp, ros::Duration(1.0), ros::Duration(0.1));
00061 tfListener.lookupTransform(mapFrame, scan.header.frame_id, scanStamp, transform);
00062
00063 const tf::Vector3 rayStart = transform(tf::Vector3(0,0,0));
00064 const float dist(min(end, maxRange));
00065 const tf::Vector3 rayEnd = transform(tf::Vector3(cosf(angle) * dist, sinf(angle) * dist, 0));
00066
00067 probMap.lineScan(
00068 Vector(rayStart.x(), rayStart.y()),
00069 Vector(rayEnd.x(), rayEnd.y()),
00070 probUpdater
00071 );
00072 if (range == end)
00073 probMap.addNearestValueSaturated(Vector(rayEnd.x(),
00074 rayEnd.y()), obsVal-freeVal);
00075 knownMap.lineScan(
00076 Vector(rayStart.x(), rayStart.y()),
00077 Vector(rayEnd.x(), rayEnd.y()),
00078 knownUpdater,
00079 0
00080 );
00081 }
00082 angle += scan.angle_increment;
00083 }
00084
00085 mapPub.publish(probMap.toOccupancyGrid(mapFrame, &knownMap));
00086 }
00087 };
00088
00089 int main(int argc, char* argv[])
00090 {
00091 ros::init(argc, argv, "occupancy_grid_builder");
00092 OccupancyGridBuilder ogb;
00093 while (ros::ok())
00094 {
00095 try
00096 {
00097 ros::spin();
00098 }
00099 catch (const tf::TransformException& e)
00100 {
00101 ROS_WARN_STREAM(e.what());
00102 }
00103 }
00104 return 0;
00105 }