sick_tim551/main.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <ros/publisher.h>
3 #include <cmath>
4 #include <pcl/point_types.h>
5 #include <pcl_ros/point_cloud.h>
6 #include <sensor_msgs/LaserScan.h>
7 #include <laser_geometry/laser_geometry.h>
8 
9 ros::Publisher _pointcloud_pub;
10 laser_geometry::LaserProjection proj;
11 
12 void scanCallback(const sensor_msgs::LaserScan::ConstPtr& msg)
13 {
14  sensor_msgs::PointCloud2 cloud;
15  proj.projectLaser(*msg, cloud);
16  cloud.header.frame_id = "/lidar";
17  _pointcloud_pub.publish(cloud);
18 }
19 
20 int main(int argc, char** argv)
21 {
22  ros::init(argc, argv, "lidar");
23 
24  ros::NodeHandle nh;
25 
26  _pointcloud_pub = nh.advertise<sensor_msgs::PointCloud2>("/pointcloud/lidar", 1);
27 
28  ros::Subscriber scan_sub = nh.subscribe("/scan", 1, scanCallback);
29 
30  ros::spin();
31 }
32 
sensor_msgs::PointCloud2 cloud
Definition: map/main.cpp:12
int main(int argc, char **argv)
laser_geometry::LaserProjection proj
void scanCallback(const sensor_msgs::LaserScan::ConstPtr &msg)
ros::Publisher _pointcloud_pub


igvc
Author(s): Matthew Barulic , Al Chaussee
autogenerated on Sun May 10 2015 16:18:45