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
00039 #ifndef KARTO_SCAN_MATCHER_KARTO_SCAN_MATCHER_H
00040 #define KARTO_SCAN_MATCHER_KARTO_SCAN_MATCHER_H
00041
00042 #include <karto/Mapper.h>
00043
00044 #undef forEach
00045 #undef forEachAs
00046 #undef const_forEach
00047 #undef const_forEachAs
00048 #undef forEachR
00049 #undef const_forEachR
00050
00051 #include <ros/ros.h>
00052 #include <tf/transform_listener.h>
00053 #include <sensor_msgs/LaserScan.h>
00054 #include <geometry_msgs/Pose2D.h>
00055 #include <boost/shared_ptr.hpp>
00056 #include <boost/optional.hpp>
00057 #include <vector>
00058 #include <Eigen/Dense>
00059
00060
00061
00062 namespace karto_scan_matcher
00063 {
00064
00065 using std::vector;
00066
00068 const double DEFAULT_SMEAR_DEVIATION = 0.03;
00069 const double DEFAULT_RANGE_THRESHOLD = 12.0;
00070
00071
00076 struct ScanWithPose
00077 {
00078 ScanWithPose (const sensor_msgs::LaserScan& scan, const geometry_msgs::Pose2D& pose)
00079 : scan(scan), pose(pose) {}
00080 ScanWithPose () {}
00081
00082 sensor_msgs::LaserScan scan;
00083 geometry_msgs::Pose2D pose;
00084 };
00085
00087 struct ScanMatchResult
00088 {
00089 ScanMatchResult (const geometry_msgs::Pose2D& pose, const Eigen::Matrix3f& cov,
00090 const double response) :
00091 pose(pose), cov(cov), response(response)
00092 {}
00093
00094 ScanMatchResult () {}
00095
00096 geometry_msgs::Pose2D pose;
00097 Eigen::Matrix3f cov;
00098 double response;
00099 };
00100
00101
00102 typedef std::vector<double> DoubleVector;
00103
00111 class KartoScanMatcher
00112 {
00113 public:
00114
00123 KartoScanMatcher(const sensor_msgs::LaserScan& init_scan, const tf::TransformListener& tf,
00124 double search_space_size, double search_grid_resolution);
00125
00134 KartoScanMatcher(const sensor_msgs::LaserScan& init_scan, const geometry_msgs::Pose2D& laser_pose,
00135 double search_space_size, double search_grid_resolution);
00136
00146 KartoScanMatcher(const sensor_msgs::LaserScan& init_scan, const geometry_msgs::Pose2D& laser_pose,
00147 const DoubleVector& search_sizes, const DoubleVector& search_resolutions);
00148
00149
00158 ScanMatchResult scanMatch (const sensor_msgs::LaserScan& scan, const geometry_msgs::Pose2D& pose,
00159 const vector<ScanWithPose>& reference_scans) const;
00160
00161
00162
00163
00165 void setPenalizeDistance (bool penalize);
00166
00169 void setVisualizationPublisher (const std::string& topic,
00170 const std::string& frame);
00171
00172 private:
00173
00174 void initialize (const sensor_msgs::LaserScan& init_scan, const geometry_msgs::Pose2D& laser_pose,
00175 const DoubleVector& search_space_sizes, const DoubleVector& search_space_resolutions);
00176
00177 void visualizeResult (const sensor_msgs::LaserScan& scan, const geometry_msgs::Pose2D& pose,
00178 const vector<ScanWithPose>& reference_scans, const geometry_msgs::Pose2D& res) const;
00179
00180
00181 typedef boost::shared_ptr<karto::ScanMatcher> MatcherPtr;
00182 typedef boost::shared_ptr<karto::Mapper> MapperPtr;
00183
00184 boost::shared_ptr<karto::Dataset> dataset_;
00185 std::vector<MatcherPtr> matchers_;
00186 std::vector<MapperPtr> mappers_;
00187 karto::LaserRangeFinder* laser_;
00188 boost::optional<ros::Publisher> vis_pub_;
00189 std::string vis_frame_;
00190
00191 bool penalize_distance_;
00192 btTransform laser_to_base_;
00193 };
00194
00195
00196 }
00197
00198
00199
00200 #endif // include guard