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/constraint_generator.h> 00041 #include <geometry_msgs/PoseWithCovarianceStamped.h> 00042 #include <ros/ros.h> 00043 #include <boost/optional.hpp> 00044 00045 namespace graph_slam 00046 { 00047 00048 const double LOCALIZATION_RECENCY_THRESHOLD = 1.0; 00049 00050 class FakeLoopClosureGenerator: public ConstraintGenerator 00051 { 00052 public: 00053 00054 FakeLoopClosureGenerator (double proximity_threshold); 00055 NodeConstraintVector getConstraints (const pose_graph::PoseGraph& graph, const pose_graph::NodeId new_node, 00056 const pose_graph::NodePoseMap& optimized_poses); 00057 void initializeFromGraph (const pose_graph::PoseGraph& g, const std::vector<pose_graph::NodeId>& node_sequence); 00058 void updateLocalization (const graph_slam::GraphLocalization& loc); 00059 00060 private: 00061 00062 void locCB (const geometry_msgs::PoseWithCovarianceStamped& msg); 00063 bool haveRecentlyReceivedPose () const; 00064 00065 /**************************************** 00066 * Associated objects 00067 ****************************************/ 00068 00069 ros::NodeHandle nh_; 00070 ros::Subscriber fake_loc_sub_; 00071 00072 /**************************************** 00073 * Params 00074 ****************************************/ 00075 00076 const double proximity_threshold_; 00077 00078 /**************************************** 00079 * State 00080 ****************************************/ 00081 00082 boost::optional<geometry_msgs::PoseStamped> last_pose_; 00083 NodePoseMap true_poses_; 00084 00085 }; 00086 00087 00088 } // namespace graph_slam 00089 00090