00001 /* 00002 * Polar Scan Matcher 00003 * Copyright (C) 2010, CCNY Robotics Lab 00004 * Ivan Dryanovski <ivan.dryanovski@gmail.com> 00005 * William Morris <morris@ee.ccny.cuny.edu> 00006 * http://robotics.ccny.cuny.edu 00007 * 00008 * This program is free software: you can redistribute it and/or modify 00009 * it under the terms of the GNU General Public License as published by 00010 * the Free Software Foundation, either version 3 of the License, or 00011 * (at your option) any later version. 00012 * 00013 * This program is distributed in the hope that it will be useful, 00014 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00015 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00016 * GNU General Public License for more details. 00017 * 00018 * You should have received a copy of the GNU General Public License 00019 * along with this program. If not, see <http://www.gnu.org/licenses/>. 00020 * 00021 * This is a wrapper around Polar Scan Matcher [1], written by 00022 * Albert Diosi 00023 * 00024 * [1] A. Diosi and L. Kleeman, "Laser Scan Matching in Polar Coordinates with 00025 * Application to SLAM " Proceedings of 2005 IEEE/RSJ International Conference 00026 * on Intelligent Robots and Systems, August, 2005, Edmonton, Canada 00027 */ 00028 00029 #ifndef POLAR_SCAN_MATCHER_PSM_NODE_H 00030 #define POLAR_SCAN_MATCHER_PSM_NODE_H 00031 00032 #include <sys/time.h> 00033 00034 #include <ros/ros.h> 00035 #include <tf/transform_broadcaster.h> 00036 #include <tf/transform_listener.h> 00037 #include <sensor_msgs/LaserScan.h> 00038 #include <sensor_msgs/Imu.h> 00039 #include <geometry_msgs/Pose2D.h> 00040 00041 #include "polar_scan_matcher/polar_match.h" 00042 00043 const std::string imuTopic_ = "imu"; 00044 const std::string scanTopic_ = "scan"; 00045 const std::string poseTopic_ = "pose2D"; 00046 00047 const double ROS_TO_PM = 100.0; // convert from cm to m 00048 00049 class PSMNode 00050 { 00051 private: 00052 00053 ros::Subscriber scanSubscriber_; 00054 ros::Subscriber imuSubscriber_; 00055 ros::Publisher posePublisher_; 00056 00057 tf::TransformBroadcaster tfBroadcaster_; 00058 tf::TransformListener tfListener_; 00059 btTransform prevWorldToBase_; 00060 btTransform baseToLaser_; 00061 btTransform laserToBase_; 00062 00063 bool initialized_; 00064 double totalDuration_; 00065 int scansCount_; 00066 00067 PolarMatcher matcher_; 00068 PMScan * prevPMScan_; 00069 00070 boost::mutex imuMutex_; 00071 double prevImuAngle_; // the yaw angle when we last perfomred a scan match 00072 double currImuAngle_; // the most recent yaw angle we have received 00073 00074 // **** parameters 00075 00076 bool publishTf_; 00077 bool publishPose_; 00078 bool useTfOdometry_; 00079 bool useImuOdometry_; 00080 00081 int minValidPoints_; 00082 int searchWindow_; 00083 double maxError_; 00084 int maxIterations_; 00085 double stopCondition_; 00086 00087 std::string worldFrame_; 00088 std::string baseFrame_; 00089 std::string laserFrame_; 00090 00091 void getParams(); 00092 bool initialize(const sensor_msgs::LaserScan& scan); 00093 00094 void imuCallback (const sensor_msgs::Imu& imuMsg); 00095 void scanCallback (const sensor_msgs::LaserScan& scan); 00096 00097 void publishTf(const btTransform& transform, 00098 const ros::Time& time); 00099 void publishPose(const btTransform& transform); 00100 00101 void rosToPMScan(const sensor_msgs::LaserScan& scan, 00102 const btTransform& change, 00103 PMScan* pmScan); 00104 void pose2DToTf(const geometry_msgs::Pose2D& pose, btTransform& t); 00105 void tfToPose2D(const btTransform& t, geometry_msgs::Pose2D& pose); 00106 void getCurrentEstimatedPose(btTransform& worldToBase, 00107 const sensor_msgs::LaserScan& scanMsg); 00108 00109 public: 00110 00111 PSMNode(); 00112 virtual ~PSMNode(); 00113 }; 00114 00115 #endif // POLAR_SCAN_MATCHER_PSM_NODE_H