32 #include <nav_msgs/OccupancyGrid.h> 34 #include <sensor_msgs/LaserScan.h> 52 nav_msgs::OccupancyGrid
map;
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"));
82 double accum_duration;
83 pnh_.
param(
"accum_duration", accum_duration, 1.0);
86 pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
88 pnh_,
"map", 1,
true);
92 pnh_.param(
"width", width_param, 30);
93 height_ = width_ = width_param;
97 pnh_.param(
"resolution", resolution, 0.1);
98 map.info.resolution = resolution;
101 map.data.resize(map.info.width * map.info.height);
104 pnh_.param(
"hz", hz, 1.0);
109 void cbScan(
const sensor_msgs::LaserScan::ConstPtr& scan)
111 sensor_msgs::PointCloud2 cloud;
112 sensor_msgs::PointCloud2 cloud_global;
117 global_frame_, cloud.header.frame_id, cloud.header.stamp,
ros::Duration(0.5));
125 cloud_global, cloud_global.header.stamp));
128 if (published_ + publish_interval_ > now)
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;
152 for (
auto& cell : map.data)
155 for (
auto& pc : accum_)
159 for (; itr_x != itr_x.end(); ++itr_x, ++itr_y)
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)
167 map.data[x + y * map.info.width] = 100;
175 int main(
int argc,
char** argv)
177 ros::init(argc, argv,
"laserscan_to_map");
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_
std::string global_frame_
void push(const Points &points)
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)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ROSCPP_DECL void spin(Spinner &spinner)
tf2_ros::TransformListener tfl_
ros::Subscriber sub_scan_
bool param(const std::string ¶m_name, T ¶m_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)
void reset(const ros::Duration &duration)
PointcloudAccumurator< sensor_msgs::PointCloud2 > accum_