38 #ifndef LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H 39 #define LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H 42 #include <sensor_msgs/Imu.h> 43 #include <sensor_msgs/LaserScan.h> 44 #include <geometry_msgs/PoseStamped.h> 45 #include <geometry_msgs/Pose2D.h> 46 #include <geometry_msgs/PoseWithCovarianceStamped.h> 47 #include <geometry_msgs/PoseWithCovariance.h> 48 #include <geometry_msgs/TwistStamped.h> 49 #include <nav_msgs/Odometry.h> 53 #include <pcl/point_types.h> 54 #include <pcl/point_cloud.h> 55 #include <pcl/filters/voxel_grid.h> 164 void laserScanToLDP(
const sensor_msgs::LaserScan::ConstPtr& scan_msg,
169 void scanCallback (
const sensor_msgs::LaserScan::ConstPtr& scan_msg);
172 void odomCallback(
const nav_msgs::Odometry::ConstPtr& odom_msg);
173 void imuCallback (
const sensor_msgs::Imu::ConstPtr& imu_msg);
174 void velCallback (
const geometry_msgs::Twist::ConstPtr& twist_msg);
175 void velStmpCallback(
const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
177 void createCache (
const sensor_msgs::LaserScan::ConstPtr& scan_msg);
183 double& pr_ch_a,
double dt);
190 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H