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
00030 #include <ros/ros.h>
00031 #include <laser_geometry/laser_geometry.h>
00032 #include <nav_msgs/OccupancyGrid.h>
00033 #include <sensor_msgs/point_cloud2_iterator.h>
00034 #include <sensor_msgs/LaserScan.h>
00035 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00036 #include <tf2_ros/transform_listener.h>
00037 #include <tf2_sensor_msgs/tf2_sensor_msgs.h>
00038
00039 #include <string>
00040
00041 #include <costmap_cspace/pointcloud_accumulator/accumulator.h>
00042 #include <neonavigation_common/compatibility.h>
00043
00044 class LaserscanToMapNode
00045 {
00046 private:
00047 ros::NodeHandle nh_;
00048 ros::NodeHandle pnh_;
00049 ros::Publisher pub_map_;
00050 ros::Subscriber sub_scan_;
00051
00052 nav_msgs::OccupancyGrid map;
00053 tf2_ros::Buffer tfbuf_;
00054 tf2_ros::TransformListener tfl_;
00055 laser_geometry::LaserProjection projector_;
00056 ros::Time published_;
00057 ros::Duration publish_interval_;
00058
00059 double z_min_, z_max_;
00060 std::string global_frame_;
00061 std::string robot_frame_;
00062
00063 unsigned int width_;
00064 unsigned int height_;
00065 float origin_x_;
00066 float origin_y_;
00067
00068 PointcloudAccumurator<sensor_msgs::PointCloud2> accum_;
00069
00070 public:
00071 LaserscanToMapNode()
00072 : nh_()
00073 , pnh_("~")
00074 , tfl_(tfbuf_)
00075 {
00076 neonavigation_common::compat::checkCompatMode();
00077 pnh_.param("z_min", z_min_, 0.1);
00078 pnh_.param("z_max", z_max_, 1.0);
00079 pnh_.param("global_frame", global_frame_, std::string("map"));
00080 pnh_.param("robot_frame", robot_frame_, std::string("base_link"));
00081
00082 double accum_duration;
00083 pnh_.param("accum_duration", accum_duration, 1.0);
00084 accum_.reset(ros::Duration(accum_duration));
00085
00086 pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
00087 nh_, "map_local",
00088 pnh_, "map", 1, true);
00089 sub_scan_ = nh_.subscribe("scan", 2, &LaserscanToMapNode::cbScan, this);
00090
00091 int width_param;
00092 pnh_.param("width", width_param, 30);
00093 height_ = width_ = width_param;
00094 map.header.frame_id = global_frame_;
00095
00096 double resolution;
00097 pnh_.param("resolution", resolution, 0.1);
00098 map.info.resolution = resolution;
00099 map.info.width = width_;
00100 map.info.height = height_;
00101 map.data.resize(map.info.width * map.info.height);
00102
00103 double hz;
00104 pnh_.param("hz", hz, 1.0);
00105 publish_interval_ = ros::Duration(1.0 / hz);
00106 }
00107
00108 private:
00109 void cbScan(const sensor_msgs::LaserScan::ConstPtr& scan)
00110 {
00111 sensor_msgs::PointCloud2 cloud;
00112 sensor_msgs::PointCloud2 cloud_global;
00113 projector_.projectLaser(*scan, cloud);
00114 try
00115 {
00116 geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
00117 global_frame_, cloud.header.frame_id, cloud.header.stamp, ros::Duration(0.5));
00118 tf2::doTransform(cloud, cloud_global, trans);
00119 }
00120 catch (tf2::TransformException& e)
00121 {
00122 ROS_WARN("%s", e.what());
00123 }
00124 accum_.push(PointcloudAccumurator<sensor_msgs::PointCloud2>::Points(
00125 cloud_global, cloud_global.header.stamp));
00126
00127 ros::Time now = scan->header.stamp;
00128 if (published_ + publish_interval_ > now)
00129 return;
00130 published_ = now;
00131
00132 try
00133 {
00134 tf2::Stamped<tf2::Transform> trans;
00135 tf2::fromMsg(tfbuf_.lookupTransform(global_frame_, robot_frame_, ros::Time(0)), trans);
00136
00137 auto pos = trans.getOrigin();
00138 float x = static_cast<int>(pos.x() / map.info.resolution) * map.info.resolution;
00139 float y = static_cast<int>(pos.y() / map.info.resolution) * map.info.resolution;
00140 map.info.origin.position.x = x - map.info.width * map.info.resolution * 0.5;
00141 map.info.origin.position.y = y - map.info.height * map.info.resolution * 0.5;
00142 map.info.origin.position.z = 0.0;
00143 map.info.origin.orientation.w = 1.0;
00144 origin_x_ = x - width_ * map.info.resolution * 0.5;
00145 origin_y_ = y - height_ * map.info.resolution * 0.5;
00146 }
00147 catch (tf2::TransformException& e)
00148 {
00149 ROS_WARN("%s", e.what());
00150 return;
00151 }
00152 for (auto& cell : map.data)
00153 cell = 0;
00154
00155 for (auto& pc : accum_)
00156 {
00157 auto itr_x = sensor_msgs::PointCloud2ConstIterator<float>(pc, "x");
00158 auto itr_y = sensor_msgs::PointCloud2ConstIterator<float>(pc, "y");
00159 for (; itr_x != itr_x.end(); ++itr_x, ++itr_y)
00160 {
00161 unsigned int x = int(
00162 (*itr_x - map.info.origin.position.x) / map.info.resolution);
00163 unsigned int y = int(
00164 (*itr_y - map.info.origin.position.y) / map.info.resolution);
00165 if (x >= map.info.width || y >= map.info.height)
00166 continue;
00167 map.data[x + y * map.info.width] = 100;
00168 }
00169 }
00170
00171 pub_map_.publish(map);
00172 }
00173 };
00174
00175 int main(int argc, char** argv)
00176 {
00177 ros::init(argc, argv, "laserscan_to_map");
00178
00179 LaserscanToMapNode conv;
00180 ros::spin();
00181
00182 return 0;
00183 }