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
00040 #include <graph_slam/scan_match_localization.h>
00041 #include <pose_graph/utils.h>
00042 #include <pose_graph/transforms.h>
00043
00044 namespace graph_slam
00045 {
00046
00047 namespace gm=geometry_msgs;
00048 namespace ksm=karto_scan_matcher;
00049
00050 using namespace pose_graph;
00051
00052
00053 ScanMatchLocalization::ScanMatchLocalization (const gm::Pose2D& laser_offset, double nbd_size,
00054 const unsigned localizations_per_scan_match) :
00055 ScanManager(laser_offset), max_link_length_(nbd_size),
00056 localizations_per_scan_match_(localizations_per_scan_match)
00057 {}
00058
00059 LocalizationState ScanMatchLocalization::nextState (const LocalizationState& state,
00060 const gm::Pose& fixed_frame_pose, const LaserPtr scan,
00061 const pg::PoseGraph& graph,
00062 const NodePoseMap& optimized_poses) const
00063 {
00064
00065 WithOptimizedPoses opt(this, optimized_poses);
00066
00067
00068 if (!matcher_)
00069 matcher_.reset(new ksm::KartoScanMatcher(*scan, laser_offset_, 0.3, 0.01));
00070
00071
00072 const gm::Pose opt_ref_pose = keyValue(optimized_poses, state.ref_node);
00073 const Eigen3::Affine3d node_to_opt(poseToWorldTransform(opt_ref_pose));
00074 const Eigen3::Affine3d fixed_frame_to_node(state.node_to_fixed_frame.inverse());
00075 const Eigen3::Affine3d fixed_frame_to_opt = node_to_opt*fixed_frame_to_node;
00076
00077
00078 const gm::Pose init_pose = applyTransform(fixed_frame_to_opt, fixed_frame_pose);
00079 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Fixed frame pose is " << projectToPose2D(fixed_frame_pose)
00080 << " and optimized frame pose is " << projectToPose2D(init_pose));
00081 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Fixed frame to opt transform is " <<
00082 toString2D(fixed_frame_to_opt));
00083
00084
00085 const gm::Point barycenter_base = computeBarycenterInBaseFrame(scan);
00086 const gm::Point barycenter_fixed = pointInReferenceFrame(barycenter_base, fixed_frame_pose);
00087 const gm::Point barycenter_opt = transformPoint(fixed_frame_to_opt, barycenter_fixed);
00088 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Barycenter in fixed frame is " << barycenter_fixed);
00089
00090
00091 const NodeSet nbd = nearbyNodes(state.ref_node, barycenter_opt, graph, max_link_length_);
00092 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Neighborhood is " << toString(nbd));
00093
00094 if (nbd.size() > 0) {
00095
00096 static unsigned counter = 0;
00097
00098
00099 gm::Pose corrected_pose;
00100 if (counter++ % localizations_per_scan_match_) {
00101 corrected_pose = init_pose;
00102 ROS_DEBUG_NAMED ("localization_internal", "Not scan matching this time");
00103 }
00104 else {
00105 const ksm::ScanMatchResult res = scanMatchNodes(matcher_, init_pose, scan, nbd);
00106 corrected_pose = convertToPose(res.pose);
00107 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Scan matching returned pose " << toString(res.pose) <<
00108 " with response " << res.response);
00109 }
00110
00111
00112 Eigen3::Affine3d corrected_fixed_frame_to_opt = transformBetween(fixed_frame_pose, corrected_pose);
00113 const pg::NodeId closest = closestNode(projectToPose2D(corrected_pose), nbd);
00114 const gm::Pose closest_pose = keyValue(optimized_poses, closest);
00115 ROS_DEBUG_STREAM_NAMED ("localization_internal", "Corrected fixed frame to opt transform is "
00116 << toString2D(corrected_fixed_frame_to_opt));
00117
00118
00119 const Eigen3::Affine3d opt_to_closest(poseToWorldTransform(closest_pose).inverse());
00120 const Eigen3::Affine3d corrected_fixed_frame_to_node=opt_to_closest*corrected_fixed_frame_to_opt;
00121 const Pose new_local_pose = applyTransform(corrected_fixed_frame_to_node, fixed_frame_pose);
00122 const Eigen3::Affine3d node_to_fixed_frame(corrected_fixed_frame_to_node.inverse());
00123 ROS_DEBUG_STREAM_COND_NAMED (closest!=state.ref_node, "localization_switch", "Switching from node " <<
00124 state.ref_node << " to " << closest << "; poses are " <<
00125 toString2D(state.node_frame_pose) << " and " << toString2D(new_local_pose));
00126 return LocalizationState(closest, node_to_fixed_frame, new_local_pose, scan->header.stamp);
00127 }
00128 else {
00129 ROS_WARN_THROTTLE (3.0, "In localization update, current position had an empty neighborhood, so not updating");
00130 return state;
00131 }
00132 }
00133
00134 }