karto_laser_constraints.h
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 #ifndef POSE_GRAPH_KARTO_LASER_CONSTRAINTS_H
00041 #define POSE_GRAPH_KARTO_LASER_CONSTRAINTS_H
00042 
00043 #include <graph_slam/constraint_generator.h>
00044 #include <graph_slam/sequential_scan_matcher.h>
00045 #include <graph_slam/loop_scan_matcher.h>
00046 #include <ros/ros.h>
00047 #include <boost/thread.hpp>
00048 
00049 namespace graph_slam
00050 {
00051 
00052 namespace pg=pose_graph;
00053 
00054 typedef boost::shared_ptr<SequentialScanMatcher> SeqMatcherPtr;
00055 typedef boost::shared_ptr<LoopScanMatcher> LoopMatcherPtr;
00056 
00057 /************************************************************
00058  * implements ConstraintGenerator; generates both
00059  * "near-chain", and loop-closure constraints, all based
00060  * on the Karto scan matcher
00061  ************************************************************/
00062 
00063 class KartoLaserConstraints : public ConstraintGenerator
00064 {
00065 public:
00066 
00067   KartoLaserConstraints (double max_seq_link_length, unsigned min_seq_chain_length, 
00068                          double min_seq_link_response, double max_loop_link_length,
00069                          unsigned min_loop_chain_length, double min_loop_closure_response,
00070                          bool use_covariances);
00071 
00072   NodeConstraintVector getConstraints (const pg::PoseGraph& graph, const pg::NodeId new_node,
00073                                        const NodePoseMap& optimized_poses);
00074   void initializeFromGraph (const pg::PoseGraph& g, const std::vector<pg::NodeId>& node_sequence);
00075   void updateLocalization (const graph_slam::GraphLocalization& loc);
00076 
00077 private:
00078 
00079   NodeConstraintVector scanOdomConstraints (const pg::PoseGraph& graph, const pg::NodeId new_node,
00080                                             const geometry_msgs::Pose& pose_estimate,
00081                                             const NodePoseMap& optimized_poses);
00082   NodeConstraintVector loopConstraints (const pg::PoseGraph& graph, const pg::NodeId new_node,
00083                                         const geometry_msgs::Pose& pose_estimate,
00084                                         const NodePoseMap& optimized_poses);
00085   void possiblyInitializeMatchers (const sensor_msgs::LaserScan& scan);
00086 
00087   const double max_sequential_link_length_;
00088   const unsigned min_sequential_chain_length_;
00089   const double min_sequential_link_response_;
00090   const double max_loop_link_length_;
00091   const unsigned min_loop_chain_length_;
00092   const double min_loop_closure_response_;
00093   const bool use_covariances_;
00094 
00095   ros::NodeHandle nh_;
00096   tf::TransformListener tf_;
00097   
00098   SeqMatcherPtr seq_matcher_;
00099   LoopMatcherPtr loop_matcher_;
00100 
00101   boost::optional<pg::NodeId> last_ref_node_;
00102 
00103   // Odometric pose of the current reference node, if it's set.
00104   // Defined in the current odometric frame (which might have drifted significantly 
00105   // from the odometric frame at the time the reference node was created)
00106   geometry_msgs::Pose ref_node_odom_pose_;
00107 };
00108 
00109 } // namespace graph_slam
00110 
00111 #endif // include guard


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