Go to the documentation of this file.
32 #include <nav_msgs/OccupancyGrid.h>
34 #include <sensor_msgs/LaserScan.h>
53 nav_msgs::OccupancyGrid
map;
83 double accum_duration;
84 pnh_.
param(
"accum_duration", accum_duration, 1.0);
87 pub_map_ = neonavigation_common::compat::advertise<nav_msgs::OccupancyGrid>(
89 pnh_,
"map", 1,
true);
98 pnh_.
param(
"resolution", resolution, 0.1);
99 map.info.resolution = resolution;
102 map.data.resize(
map.info.width *
map.info.height);
110 void cbScan(
const sensor_msgs::LaserScan::ConstPtr& scan)
112 sensor_msgs::PointCloud2 cloud;
113 sensor_msgs::PointCloud2 cloud_global;
126 cloud_global, cloud_global.header.stamp));
139 auto pos = trans.getOrigin();
140 float x =
static_cast<int>(pos.x() /
map.info.resolution) *
map.info.resolution;
141 float y =
static_cast<int>(pos.y() /
map.info.resolution) *
map.info.resolution;
142 map.info.origin.position.x = x -
map.info.width *
map.info.resolution * 0.5;
143 map.info.origin.position.y = y -
map.info.height *
map.info.resolution * 0.5;
144 map.info.origin.position.z = 0.0;
145 map.info.origin.orientation.w = 1.0;
155 for (
auto& cell :
map.data)
163 for (; itr_x != itr_x.end(); ++itr_x, ++itr_y)
165 if (*itr_z - robot_z <
z_min_ ||
z_max_ < *itr_z - robot_z)
167 unsigned int x = int(
168 (*itr_x -
map.info.origin.position.x) /
map.info.resolution);
169 unsigned int y = int(
170 (*itr_y -
map.info.origin.position.y) /
map.info.resolution);
171 if (x >=
map.info.width || y >=
map.info.height)
173 map.data[x + y *
map.info.width] = 100;
181 int main(
int argc,
char** argv)
183 ros::init(argc, argv,
"laserscan_to_map");
void reset(const ros::Duration &duration)
void push(const Points &points)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::Duration publish_interval_
void fromMsg(const A &, B &b)
nav_msgs::OccupancyGrid map
void publish(const boost::shared_ptr< M > &message) const
costmap_cspace::PointcloudAccumulator< sensor_msgs::PointCloud2 > accum_
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
int main(int argc, char **argv)
tf2_ros::TransformListener tfl_
ros::Subscriber sub_scan_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
laser_geometry::LaserProjection projector_
std::string global_frame_
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
void cbScan(const sensor_msgs::LaserScan::ConstPtr &scan)
T param(const std::string ¶m_name, const T &default_val) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:10