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
00039 #ifndef LASER_SLAM_SCAN_MATCH_LOCALIZATION_H
00040 #define LASER_SLAM_SCAN_MATCH_LOCALIZATION_H
00041
00042 #include <laser_slam/scan_matching.h>
00043 #include <laser_slam/LocalizedScan.h>
00044 #include <pose_graph/graph_db.h>
00045 #include <pose_graph/diff_subscriber.h>
00046 #include <graph_mapping_msgs/LocalizationDistribution.h>
00047 #include <graph_mapping_msgs/NodePoses.h>
00048 #include <geometry_msgs/Pose2D.h>
00049 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00050 #include <kidnapped_robot/MatchResult.h>
00051 #include <tf/transform_listener.h>
00052 #include <boost/thread.hpp>
00053 #include <boost/optional.hpp>
00054
00055 namespace laser_slam
00056 {
00057
00058 namespace msg=graph_mapping_msgs;
00059 namespace pg=pose_graph;
00060
00062 class ScanMatchLocalizer
00063 {
00064 public:
00065 ScanMatchLocalizer (ros::NodeHandle param_nh,
00066 boost::shared_ptr<tf::TransformListener> tf);
00067
00068 private:
00069
00070 void update (const ros::TimerEvent& e);
00071 void updateUsingFixedFrame ();
00072 void storeScan (sensor_msgs::LaserScan::ConstPtr scan);
00073 void diffCB (boost::optional<const msg::ConstraintGraphDiff&> diff,
00074 const pg::ConstraintGraph& graph);
00075 void matchCB (const kidnapped_robot::MatchResult& match);
00076 boost::optional<tf::StampedTransform> fixedFramePoseAt (const ros::Time& t);
00077 void setInitialPose (const geometry_msgs::PoseWithCovarianceStamped& m);
00078 void recomputeOptimizedPoses (pg::ConstraintGraph* g, const pg::NodeSet& comp);
00079 void adjustInitialPose (const tf::Pose& p, const pose_graph::ConstraintGraph& g,
00080 const pose_graph::NodeSet& comp,
00081 double global_loc_radius);
00082 unsigned closestNode (const pg::ConstraintGraph& g,
00083 const pg::NodeSet& nodes,
00084 const btVector3& barycenter) const;
00085 bool closerTo (const pg::ConstraintGraph& g,
00086 const btVector3& barycenter,
00087 const unsigned n1, const unsigned n2) const;
00088
00089
00090
00091
00092
00093 mutable boost::mutex mutex_;
00094 ros::NodeHandle param_nh_;
00095 tf::Pose laser_offset_;
00096 const double update_rate_;
00097 const double scan_match_proportion_;
00098 const double max_nbd_size_;
00099 const std::string fixed_frame_;
00100 const std::string base_frame_;
00101 const std::string opt_frame_;
00102 const double window_size_;
00103 const double odom_noise_;
00104 const double match_radius_;
00105 const double match_resolution_;
00106 const double angular_resolution_;
00107 const bool do_global_localization_;
00108
00109
00110
00111
00112
00113 msg::LocalizationDistribution::Ptr last_loc_;
00114 bool initialized_;
00115 sensor_msgs::LaserScan::ConstPtr last_scan_, initialization_scan_;
00116
00117
00118
00119 pg::NodePoseMap opt_poses_;
00120 bool optimize_flag_;
00121 unsigned match_count_;
00122 boost::optional<ros::Time> last_match_request_time_;
00123 boost::optional<kidnapped_robot::MatchResult> match_result_;
00124
00125
00126
00127
00128
00129
00130 boost::shared_ptr<tf::TransformListener> tf_;
00131 warehouse::WarehouseClient db_;
00132 const ScanMap scans_;
00133 const pose_graph::CachedNodeMap<geometry_msgs::Pose> ff_poses_;
00134 MatcherPtr matcher_;
00135 ros::NodeHandle nh_;
00136 ros::Publisher loc_pub_, image_save_pub_, match_req_pub_;
00137 ros::Subscriber init_pose_sub_, scan_sub_, match_sub_;
00138 pg::DiffSubscriber diff_sub_;
00139 ros::ServiceClient get_poses_client_;
00140 ros::Timer update_timer_;
00141 };
00142
00143 const double GLOBAL_MATCH_MIN_RESPONSE=0.6;
00144
00145 }
00146
00147 #endif // include guard