scan_match_localization.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage, Inc. 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 
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   // Set optimized poses during this function
00065   WithOptimizedPoses opt(this, optimized_poses);
00066   
00067   // Initialize matcher if necessary
00068   if (!matcher_)
00069     matcher_.reset(new ksm::KartoScanMatcher(*scan, laser_offset_, 0.3, 0.01));
00070   
00071   // Identify transform between fixed frame and implicit frame of the optimized poses
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   // Initial estimate of current pose in optimized frame
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   // Barycenter
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   // Nodes that we'll scan match against
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     // Do the scan matching
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     // Figure out the new closest node
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     // Return updated state
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 } // namespace graph_slam


graph_slam
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:21