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/Pose2D.h>
00045 #include <geometry_msgs/Twist.h>
00046 #include <nav_msgs/Odometry.h>
00047 #include <tf/transform_datatypes.h>
00048 #include <tf/transform_listener.h>
00049 #include <tf/transform_broadcaster.h>
00050
00051 #include <pcl/point_types.h>
00052 #include <pcl/point_cloud.h>
00053 #include <pcl_ros/point_cloud.h>
00054
00055 #include <csm/csm_all.h>
00056 #undef min
00057 #undef max
00058
00059 namespace scan_tools
00060 {
00061
00062
00063 const std::string scan_topic_ = "scan";
00064 const std::string cloud_topic_ = "cloud";
00065 const std::string odom_topic_ = "odom";
00066 const std::string imu_topic_ = "imu";
00067
00068
00069 const std::string pose_topic_ = "pose2D";
00070
00071 typedef pcl::PointXYZ PointT;
00072 typedef pcl::PointCloud<PointT> PointCloudT;
00073
00074 class LaserScanMatcher
00075 {
00076 private:
00077
00078
00079
00080 ros::NodeHandle nh_;
00081 ros::NodeHandle nh_private_;
00082
00083 ros::Subscriber scan_subscriber_;
00084 ros::Subscriber cloud_subscriber_;
00085 ros::Subscriber odom_subscriber_;
00086 ros::Subscriber imu_subscriber_;
00087
00088 tf::TransformListener tf_listener_;
00089 tf::TransformBroadcaster tf_broadcaster_;
00090
00091 tf::Transform base_to_laser_;
00092 tf::Transform laser_to_base_;
00093
00094 ros::Publisher test_pub_;
00095 ros::Publisher pose_publisher_;
00096 ros::Publisher vel_publisher_;
00097
00098
00099
00100 std::string base_frame_;
00101 std::string fixed_frame_;
00102 double cloud_range_min_;
00103 double cloud_range_max_;
00104 bool publish_tf_;
00105 bool publish_pose_;
00106
00107 bool use_cloud_input_;
00108
00109
00110
00111
00112
00113
00114
00115 bool use_imu_;
00116 bool use_odom_;
00117 bool use_alpha_beta_;
00118
00119 double alpha_;
00120 double beta_;
00121
00122
00123
00124 bool initialized_;
00125
00126 bool received_imu_;
00127 bool received_odom_;
00128
00129 boost::mutex mutex_;
00130
00131 tf::Transform w2b_;
00132
00133 double v_x_;
00134 double v_y_;
00135 double v_a_;
00136
00137 ros::Time last_icp_time_;
00138
00139 double latest_imu_yaw_;
00140 double last_imu_yaw_;
00141
00142 nav_msgs::Odometry latest_odom_;
00143 nav_msgs::Odometry last_odom_;
00144
00145 std::vector<double> a_cos_;
00146 std::vector<double> a_sin_;
00147
00148 sm_params input_;
00149 sm_result output_;
00150 LDP prev_ldp_scan_;
00151
00152
00153
00154 void processScan(LDP& curr_ldp_scan, const ros::Time& time);
00155
00156 void laserScanToLDP(const sensor_msgs::LaserScan::ConstPtr& scan_msg,
00157 LDP& ldp);
00158 void PointCloudToLDP(const PointCloudT::ConstPtr& cloud,
00159 LDP& ldp);
00160
00161 void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
00162 void cloudCallback (const PointCloudT::ConstPtr& cloud);
00163
00164 void odomCallback (const nav_msgs::Odometry::ConstPtr& odom_msg);
00165 void imuCallback (const sensor_msgs::ImuPtr& imu_msg);
00166
00167 void createCache (const sensor_msgs::LaserScan::ConstPtr& scan_msg);
00168 bool getBaseToLaserTf (const std::string& frame_id);
00169 void initParams();
00170
00171 void getPrediction(double& pr_ch_x, double& pr_ch_y,
00172 double& pr_ch_a, double dt);
00173
00174 double getYawFromQuaternion(const geometry_msgs::Quaternion& quaternion);
00175 double getYawFromQuaternion(const tf::Quaternion& quaternion);
00176 void createTfFromXYTheta(double x, double y, double theta, tf::Transform& t);
00177
00178 public:
00179
00180 LaserScanMatcher(ros::NodeHandle nh, ros::NodeHandle nh_private);
00181 ~LaserScanMatcher();
00182 };
00183
00184 }
00185
00186 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H