karto_laser_constraint_generator.cpp
Go to the documentation of this file.
00001 /* Copyright (c) 2008, Willow Garage, Inc.
00002  * All rights reserved.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *
00007  *     * Redistributions of source code must retain the above copyright
00008  *       notice, this list of conditions and the following disclaimer.
00009  *     * Redistributions in binary form must reproduce the above copyright
00010  *       notice, this list of conditions and the following disclaimer in the
00011  *       documentation and/or other materials provided with the distribution.
00012  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00013  *       contributors may be used to endorse or promote products derived from
00014  *       this software without specific prior written permission.
00015  *
00016  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026  * POSSIBILITY OF SUCH DAMAGE.
00027  *
00028  */
00029 
00030 
00039 #include <graph_slam/constraints/karto_laser_constraints.h>
00040 #include <pose_graph/transforms.h>
00041 #include <pose_graph/utils.h>
00042 #include <pose_graph/geometry.h>
00043 #include <boost/foreach.hpp>
00044 #include <boost/bind.hpp>
00045 #include <boost/ref.hpp>
00046 #include <queue>
00047 
00048 namespace graph_slam
00049 {
00050 
00051 namespace ksm=karto_scan_matcher;
00052 namespace sm=sensor_msgs;
00053 namespace gm=geometry_msgs;
00054 namespace pg=pose_graph;
00055 
00056 using namespace pg;
00057 
00058 using std::vector;
00059 using std::set;
00060 using boost::bind;
00061 using boost::ref;
00062 using graph_slam::GraphLocalization;
00063 
00064 typedef set<NodeId> NodeSet;
00065 typedef vector<Chain> ChainVec;
00066 
00067 KartoLaserConstraints::KartoLaserConstraints (const double max_seq_link_length, 
00068                                               const unsigned min_seq_chain_length, const double min_seq_response,
00069                                               const double max_loop_link_length,
00070                                               const unsigned min_loop_chain_length,
00071                                               const double min_loop_response, const bool use_covariances) :
00072   max_sequential_link_length_(max_seq_link_length), min_sequential_chain_length_(min_seq_chain_length),
00073   min_sequential_link_response_(min_seq_response), max_loop_link_length_(max_loop_link_length),
00074   min_loop_chain_length_(min_loop_chain_length), min_loop_closure_response_(min_loop_response),
00075   use_covariances_(use_covariances), tf_(nh_)
00076 {
00077 }
00078 
00079 bool targetIs (const NodeConstraint& constraint, const NodeId n)
00080 {
00081   return (constraint.target == n);
00082 }
00083 
00084 // Get the laser's pose, relative to base.
00085 gm::Pose2D getLaserOffset (const tf::TransformListener& tf, const sm::LaserScan& scan)
00086 {
00087   tf::Stamped<tf::Pose> ident;
00088   tf::Stamped<btTransform> laser_to_base;
00089   ident.setIdentity();
00090   ident.frame_id_ = scan.header.frame_id;
00091   ident.stamp_ = ros::Time();
00092   
00093   if (!tf.waitForTransform("base_link", ident.frame_id_, ros::Time(), ros::Duration(5.0))) {
00094     ROS_FATAL_STREAM ("Didn't get a transform between base_link and " << ident.frame_id_ << " in time");
00095     ROS_BREAK();
00096   }
00097   
00098   tf.transformPose("base_link", ident, laser_to_base);
00099 
00100   gm::Pose2D laser_pose;
00101   laser_pose.x = laser_to_base.getOrigin().x();
00102   laser_pose.y = laser_to_base.getOrigin().y();
00103   laser_pose.theta = tf::getYaw(laser_to_base.getRotation());
00104   return laser_pose;
00105 }
00106 
00107 
00108 void KartoLaserConstraints::possiblyInitializeMatchers (const sm::LaserScan& scan) 
00109 {
00110   if (!seq_matcher_) {
00111     ROS_ASSERT (!loop_matcher_);
00112     const gm::Pose2D offset = getLaserOffset(tf_, scan);
00113     seq_matcher_.reset(new SequentialScanMatcher(offset, max_sequential_link_length_,
00114                                                  min_sequential_chain_length_, min_sequential_link_response_,
00115                                                  use_covariances_));
00116     loop_matcher_.reset(new LoopScanMatcher(offset, max_loop_link_length_, min_loop_chain_length_,
00117                                             min_loop_closure_response_, use_covariances_));
00118   }
00119 }
00120 
00121 
00122 // Externally called method that returns sequential and loop constraints
00123 NodeConstraintVector KartoLaserConstraints::getConstraints (const PoseGraph& graph, const NodeId new_node,
00124                                                             const NodePoseMap& optimized_poses)
00125 {
00126   ROS_DEBUG_STREAM_NAMED ("karto", "Getting constraints for " << new_node);
00127   const sm::LaserScan::ConstPtr scan = graph.getScan(new_node);
00128   possiblyInitializeMatchers(*scan);
00129   NodeConstraintVector constraints;
00130   const gm::Pose odom_pose=graph.getInitialPoseEstimate(new_node);    
00131 
00132   if (last_ref_node_) {
00133     const gm::Pose rel_odom = relativePose(odom_pose, ref_node_odom_pose_);
00134     const Eigen3::Affine3d trans = poseToWorldTransform(keyValue(optimized_poses, *last_ref_node_));
00135     const gm::Pose init_pose = applyTransform(trans, rel_odom);
00136     NodeConstraintVector scan_odom_constraints = scanOdomConstraints(graph, new_node, init_pose, optimized_poses);
00137     NodeConstraintVector loop_constraints = loopConstraints(graph, new_node, init_pose, optimized_poses);
00138     constraints.insert(constraints.end(), scan_odom_constraints.begin(), scan_odom_constraints.end());
00139     constraints.insert(constraints.end(), loop_constraints.begin(), loop_constraints.end());
00140   }
00141   
00142   seq_matcher_->addNode(new_node, scan);
00143   loop_matcher_->addNode(new_node, scan);
00144 
00145   last_ref_node_ = new_node;
00146   ref_node_odom_pose_ = odom_pose;
00147   seq_matcher_->addRunningNode(new_node);
00148 
00149   return constraints;
00150 }
00151 
00152 void KartoLaserConstraints::updateLocalization (const GraphLocalization& graph_loc)
00153 {
00154   seq_matcher_->resetLastNode();
00155   loop_matcher_->resetLastNode();
00156   last_ref_node_ = NodeId(graph_loc.node);
00157   const Eigen3::Affine3d ref_to_fixed_frame = transformBetween(graph_loc.offset, graph_loc.fixed_frame_pose);
00158   gm::Pose id;
00159   id.orientation.w = 1.0;
00160   ref_node_odom_pose_ = applyTransform(ref_to_fixed_frame, id);
00161   seq_matcher_->addRunningNode(*last_ref_node_);
00162 }
00163 
00164 
00165 void KartoLaserConstraints::initializeFromGraph (const PoseGraph& g, const vector<NodeId>& node_sequence)
00166 {
00167   BOOST_FOREACH (const NodeId n, g.allNodes()) {
00168     ROS_ASSERT (g.hasScan(n));
00169     sm::LaserScan::ConstPtr scan = g.getScan(n);
00170     possiblyInitializeMatchers(*scan);
00171     seq_matcher_->addNode(n, scan);
00172     loop_matcher_->addNode(n, scan);
00173   }
00174   seq_matcher_->resetLastNode();
00175   loop_matcher_->resetLastNode();
00176   last_ref_node_ = *(--node_sequence.end());
00177 }
00178 
00179 
00180 
00181 NodeConstraintVector KartoLaserConstraints::loopConstraints (const PoseGraph& graph,
00182                                                              const NodeId new_node,
00183                                                              const gm::Pose& pose_estimate,
00184                                                              const NodePoseMap& optimized_poses)
00185 {
00186   ROS_ASSERT(loop_matcher_);
00187   WithOptimizedPoses opt(loop_matcher_.get(), optimized_poses);
00188   NodeConstraintVector constraints =
00189     loop_matcher_->getConstraints(graph, *last_ref_node_, pose_estimate, graph.getScan(new_node));
00190   ROS_DEBUG_STREAM_NAMED ("karto", "  Adding " << constraints.size() << " loop constraints");
00191   return constraints;
00192 }
00193 
00194 NodeConstraintVector KartoLaserConstraints::scanOdomConstraints (const PoseGraph& graph,
00195                                                                  const NodeId new_node,
00196                                                                  const gm::Pose& pose_estimate,
00197                                                                  const NodePoseMap& optimized_poses)
00198 {
00199   ROS_ASSERT (seq_matcher_);
00200   WithOptimizedPoses opt(seq_matcher_.get(), optimized_poses);
00201   NodeConstraintVector constraints =
00202     seq_matcher_->getConstraints(graph, *last_ref_node_, pose_estimate, graph.getScan(new_node));
00203   ROS_DEBUG_STREAM_NAMED ("karto", "  Adding " << constraints.size() << " sequential scan constraints");
00204   return constraints;
00205 }
00206 
00207 } // namespace graph_slam


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