laserscan_to_map.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
32 #include <nav_msgs/OccupancyGrid.h>
34 #include <sensor_msgs/LaserScan.h>
38 
39 #include <string>
40 
43 
45 {
46 private:
51 
52  nav_msgs::OccupancyGrid map;
58 
59  double z_min_, z_max_;
60  std::string global_frame_;
61  std::string robot_frame_;
62 
63  unsigned int width_;
64  unsigned int height_;
65  float origin_x_;
66  float origin_y_;
67 
69 
70 public:
72  : nh_()
73  , pnh_("~")
74  , tfl_(tfbuf_)
75  {
77  pnh_.param("z_min", z_min_, 0.1);
78  pnh_.param("z_max", z_max_, 1.0);
79  pnh_.param("global_frame", global_frame_, std::string("map"));
80  pnh_.param("robot_frame", robot_frame_, std::string("base_link"));
81 
82  double accum_duration;
83  pnh_.param("accum_duration", accum_duration, 1.0);
84  accum_.reset(ros::Duration(accum_duration));
85 
86  pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
87  nh_, "map_local",
88  pnh_, "map", 1, true);
89  sub_scan_ = nh_.subscribe("scan", 2, &LaserscanToMapNode::cbScan, this);
90 
91  int width_param;
92  pnh_.param("width", width_param, 30);
93  height_ = width_ = width_param;
94  map.header.frame_id = global_frame_;
95 
96  double resolution;
97  pnh_.param("resolution", resolution, 0.1);
98  map.info.resolution = resolution;
99  map.info.width = width_;
100  map.info.height = height_;
101  map.data.resize(map.info.width * map.info.height);
102 
103  double hz;
104  pnh_.param("hz", hz, 1.0);
105  publish_interval_ = ros::Duration(1.0 / hz);
106  }
107 
108 private:
109  void cbScan(const sensor_msgs::LaserScan::ConstPtr& scan)
110  {
111  sensor_msgs::PointCloud2 cloud;
112  sensor_msgs::PointCloud2 cloud_global;
113  projector_.projectLaser(*scan, cloud);
114  try
115  {
116  geometry_msgs::TransformStamped trans = tfbuf_.lookupTransform(
117  global_frame_, cloud.header.frame_id, cloud.header.stamp, ros::Duration(0.5));
118  tf2::doTransform(cloud, cloud_global, trans);
119  }
120  catch (tf2::TransformException& e)
121  {
122  ROS_WARN("%s", e.what());
123  }
125  cloud_global, cloud_global.header.stamp));
126 
127  ros::Time now = scan->header.stamp;
128  if (published_ + publish_interval_ > now)
129  return;
130  published_ = now;
131 
132  try
133  {
135  tf2::fromMsg(tfbuf_.lookupTransform(global_frame_, robot_frame_, ros::Time(0)), trans);
136 
137  auto pos = trans.getOrigin();
138  float x = static_cast<int>(pos.x() / map.info.resolution) * map.info.resolution;
139  float y = static_cast<int>(pos.y() / map.info.resolution) * map.info.resolution;
140  map.info.origin.position.x = x - map.info.width * map.info.resolution * 0.5;
141  map.info.origin.position.y = y - map.info.height * map.info.resolution * 0.5;
142  map.info.origin.position.z = 0.0;
143  map.info.origin.orientation.w = 1.0;
144  origin_x_ = x - width_ * map.info.resolution * 0.5;
145  origin_y_ = y - height_ * map.info.resolution * 0.5;
146  }
147  catch (tf2::TransformException& e)
148  {
149  ROS_WARN("%s", e.what());
150  return;
151  }
152  for (auto& cell : map.data)
153  cell = 0;
154 
155  for (auto& pc : accum_)
156  {
157  auto itr_x = sensor_msgs::PointCloud2ConstIterator<float>(pc, "x");
158  auto itr_y = sensor_msgs::PointCloud2ConstIterator<float>(pc, "y");
159  for (; itr_x != itr_x.end(); ++itr_x, ++itr_y)
160  {
161  unsigned int x = int(
162  (*itr_x - map.info.origin.position.x) / map.info.resolution);
163  unsigned int y = int(
164  (*itr_y - map.info.origin.position.y) / map.info.resolution);
165  if (x >= map.info.width || y >= map.info.height)
166  continue;
167  map.data[x + y * map.info.width] = 100;
168  }
169  }
170 
171  pub_map_.publish(map);
172  }
173 };
174 
175 int main(int argc, char** argv)
176 {
177  ros::init(argc, argv, "laserscan_to_map");
178 
179  LaserscanToMapNode conv;
180  ros::spin();
181 
182  return 0;
183 }
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
void publish(const boost::shared_ptr< M > &message) const
laser_geometry::LaserProjection projector_
void push(const Points &points)
Definition: accumulator.h:73
nav_msgs::OccupancyGrid map
int main(int argc, char **argv)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ros::Publisher pub_map_
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
tf2_ros::Buffer tfbuf_
ros::NodeHandle nh_
ROSCPP_DECL void spin(Spinner &spinner)
tf2_ros::TransformListener tfl_
ros::Subscriber sub_scan_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void fromMsg(const A &, B &b)
ros::Duration publish_interval_
TFSIMD_FORCE_INLINE const tfScalar & x() const
void cbScan(const sensor_msgs::LaserScan::ConstPtr &scan)
ros::NodeHandle pnh_
void reset(const ros::Duration &duration)
Definition: accumulator.h:62
PointcloudAccumurator< sensor_msgs::PointCloud2 > accum_


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:48