30 #ifndef LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H 31 #define LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H 35 #include <geometry_msgs/Point32.h> 36 #include <geometry_msgs/PoseStamped.h> 37 #include <sensor_msgs/LaserScan.h> 38 #include <sensor_msgs/Imu.h> 39 #include <sensor_msgs/PointCloud2.h> 44 #include <pcl/io/pcd_io.h> 45 #include <pcl/point_types.h> 46 #include <pcl/point_cloud.h> 56 typedef geometry_msgs::PoseStamped
PoseMsg;
102 void scanCallback (
const sensor_msgs::LaserScan::ConstPtr& scan_msg);
104 void imuCallback (
const ImuMsg::ConstPtr& imu_msg);
107 void createCache (
const sensor_msgs::LaserScan::ConstPtr& scan_msg);
114 #endif // LASER_ORTHO_PROJECTOR_LASER_ORTHO_PROJECTOR_H