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