35 #include <nav_msgs/OccupancyGrid.h>
36 #include <sensor_msgs/PointCloud2.h>
53 nav_msgs::OccupancyGrid
map_;
68 std::vector<costmap_cspace::PointcloudAccumulator<sensor_msgs::PointCloud2>>
accums_;
83 double accum_duration;
84 pnh_.
param(
"accum_duration", accum_duration, 1.0);
88 pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
90 pnh_,
"map", 1,
true);
95 "cloud_singleshot", 100,
104 pnh_.
param(
"resolution", resolution, 0.1);
105 map_.info.resolution = resolution;
116 void cbCloud(
const sensor_msgs::PointCloud2::ConstPtr& cloud,
const bool singleshot)
118 sensor_msgs::PointCloud2 cloud_global;
119 geometry_msgs::TransformStamped trans;
132 const int buffer = singleshot ? 1 : 0;
134 cloud_global, cloud_global.header.stamp));
147 auto pos = trans.getOrigin();
148 float x =
static_cast<int>(pos.x() /
map_.info.resolution) *
map_.info.resolution;
149 float y =
static_cast<int>(pos.y() /
map_.info.resolution) *
map_.info.resolution;
150 map_.info.origin.position.x = x -
map_.info.width *
map_.info.resolution * 0.5;
151 map_.info.origin.position.y = y -
map_.info.height *
map_.info.resolution * 0.5;
152 map_.info.origin.position.z = 0.0;
153 map_.info.origin.orientation.w = 1.0;
163 for (
auto& cell :
map_.data)
168 for (
auto& pc : accum)
173 for (; iter_x != iter_x.
end(); ++iter_x, ++iter_y, ++iter_z)
175 if (*iter_z - robot_z <
z_min_ ||
z_max_ < *iter_z - robot_z)
177 unsigned int x = int(
178 (*iter_x -
map_.info.origin.position.x) /
map_.info.resolution);
179 unsigned int y = int(
180 (*iter_y -
map_.info.origin.position.y) /
map_.info.resolution);
181 if (x >=
map_.info.width || y >=
map_.info.height)
183 map_.data[x + y *
map_.info.width] = 100;
192 int main(
int argc,
char** argv)
194 ros::init(argc, argv,
"pointcloud2_to_map");