laser_scan_matcher.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2011, Ivan Dryanovski, William Morris
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the CCNY Robotics Lab nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*  This package uses Canonical Scan Matcher [1], written by
00031  *  Andrea Censi
00032  *
00033  *  [1] A. Censi, "An ICP variant using a point-to-line metric"
00034  *  Proceedings of the IEEE International Conference
00035  *  on Robotics and Automation (ICRA), 2008
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>  // csm defines min and max, but Eigen complains
00057 #undef min
00058 #undef max
00059 
00060 namespace scan_tools
00061 {
00062 /*
00063 // inputs
00064 const std::string scan_topic_  = "scan";
00065 const std::string cloud_topic_ = "cloud";
00066 const std::string odom_topic_  = "odom";
00067 const std::string imu_topic_   = "imu";
00068 
00069 // outputs
00070 const std::string pose2d_topic_ = "pose2D";
00071 const std::string pose_topic_ = "poseICP";
00072 */
00073 typedef pcl::PointXYZ           PointT;
00074 typedef pcl::PointCloud<PointT> PointCloudT;
00075 
00076 class LaserScanMatcher
00077 {
00078   private:
00079 
00080     // **** ros
00081 
00082 // inputs
00083     std::string scan_topic_ ;
00084     std::string cloud_topic_;
00085     std::string odom_topic_ ;
00086     std::string imu_topic_ ;
00087 
00088 // outputs
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     // **** parameters
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     // **** What predictions are available to speed up the ICP?
00125     // 1) imu - [theta] from imu yaw angle - /odom topic
00126     // 2) odom - [x, y, theta] from wheel odometry - /imu topic
00127     // 3) alpha_beta - [x, y, theta] from simple tracking filter - no topic req.
00128     // If more than one is enabled, priority is imu > odom > alpha_beta
00129 
00130     bool use_imu_;
00131     bool use_odom_;
00132     bool use_alpha_beta_;
00133 
00134     double alpha_;
00135     double beta_;
00136 
00137     // **** state variables
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_; // world-to-base tf (pose of base frame)
00151 
00152     double v_x_;  // velocity estimated by the alpha-beta tracker
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     // **** methods
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 } //namespace
00204 
00205 #endif // LASER_SCAN_MATCHER_LASER_SCAN_MATCHER_H


iri_laser_scan_matcher
Author(s): Ivan Dryanovski, William Morris
autogenerated on Fri Dec 6 2013 22:42:22