Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 #ifndef LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
00039 #define LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H
00040 
00041 #include <ros/ros.h>
00042 #include <sensor_msgs/Imu.h>
00043 #include <sensor_msgs/LaserScan.h>
00044 #include <geometry_msgs/PoseStamped.h>
00045 #include <geometry_msgs/Pose2D.h>
00046 #include <geometry_msgs/TwistStamped.h>
00047 #include <nav_msgs/Odometry.h>
00048 #include <tf/transform_datatypes.h>
00049 #include <tf/transform_listener.h>
00050 #include <tf/transform_broadcaster.h>
00051 #include <pcl/point_types.h>
00052 #include <pcl/point_cloud.h>
00053 #include <pcl/filters/voxel_grid.h>
00054 #include <pcl_ros/point_cloud.h>
00055 
00056 #include <csm/csm_all.h>  
00057 #undef min 
00058 #undef max
00059 
00060 namespace scan_tools
00061 {
00062 
00063 class LaserScanMatcher
00064 {
00065   public:
00066 
00067     LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private);
00068     ~LaserScanMatcher();
00069 
00070   private:
00071 
00072     typedef pcl::PointXYZ           PointT;
00073     typedef pcl::PointCloud<PointT> PointCloudT;
00074 
00075     
00076 
00077     ros::NodeHandle nh_;
00078     ros::NodeHandle nh_private_;
00079 
00080     ros::Subscriber scan_subscriber_;
00081     ros::Subscriber cloud_subscriber_;
00082     ros::Subscriber odom_subscriber_;
00083     ros::Subscriber imu_subscriber_;
00084     ros::Subscriber vel_subscriber_;
00085 
00086     tf::TransformListener    tf_listener_;
00087     tf::TransformBroadcaster tf_broadcaster_;
00088 
00089     tf::Transform base_to_laser_; 
00090     tf::Transform laser_to_base_; 
00091 
00092     ros::Publisher  pose_publisher_;
00093     ros::Publisher  pose_stamped_publisher_;
00094 
00095     
00096 
00097     std::string base_frame_;
00098     std::string fixed_frame_;
00099     double cloud_range_min_;
00100     double cloud_range_max_;
00101     double cloud_res_;
00102     bool publish_tf_;
00103     bool publish_pose_;
00104     bool publish_pose_stamped_;
00105 
00106     bool use_cloud_input_;
00107 
00108     double kf_dist_linear_;
00109     double kf_dist_linear_sq_;
00110     double kf_dist_angular_;
00111 
00112     
00113     
00114     
00115     
00116     
00117 
00118     bool use_imu_;
00119     bool use_odom_;
00120     bool use_vel_;
00121 
00122     
00123 
00124     boost::mutex mutex_;
00125 
00126     bool initialized_;
00127     bool received_imu_;
00128     bool received_odom_;
00129     bool received_vel_;
00130 
00131     tf::Transform f2b_;    
00132     tf::Transform f2b_kf_; 
00133 
00134     ros::Time last_icp_time_;
00135 
00136     sensor_msgs::Imu latest_imu_msg_;
00137     sensor_msgs::Imu last_used_imu_msg_;
00138     nav_msgs::Odometry latest_odom_msg_;
00139     nav_msgs::Odometry last_used_odom_msg_;
00140 
00141     geometry_msgs::TwistStamped latest_vel_msg_;
00142     
00143     std::vector<double> a_cos_;
00144     std::vector<double> a_sin_;
00145 
00146     sm_params input_;
00147     sm_result output_;
00148     LDP prev_ldp_scan_;
00149 
00150     
00151 
00152     void initParams();
00153     void processScan(LDP& curr_ldp_scan, const ros::Time& time);
00154 
00155     void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
00156                               LDP& ldp);
00157     void PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
00158                                LDP& ldp);
00159 
00160     void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
00161     void cloudCallback (const PointCloudT::ConstPtr& cloud);
00162 
00163     void odomCallback(const nav_msgs::Odometry::ConstPtr& odom_msg);
00164     void imuCallback (const sensor_msgs::Imu::ConstPtr& imu_msg);
00165     void velCallback (const geometry_msgs::TwistStamped::ConstPtr& twist_msg);
00166 
00167     void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
00168     bool getBaseToLaserTf (const std::string& frame_id);
00169 
00170     bool newKeyframeNeeded(const tf::Transform& d);
00171 
00172     void getPrediction(double& pr_ch_x, double& pr_ch_y, 
00173                        double& pr_ch_a, double dt);
00174 
00175     void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
00176 };
00177 
00178 } 
00179 
00180 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H