fake_loop_closure.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/constraints/fake_loop_closure.h>
00041 #include <pose_graph/utils.h>
00042 #include <pose_graph/transforms.h>
00043 #include <boost/foreach.hpp>
00044 
00045 namespace graph_slam
00046 {
00047 
00048 namespace gm=geometry_msgs;
00049 namespace pg=pose_graph;
00050 
00051 
00052 FakeLoopClosureGenerator::FakeLoopClosureGenerator (const double proximity_threshold) :
00053   fake_loc_sub_(nh_.subscribe("fake_localization", 1, &FakeLoopClosureGenerator::locCB, this)),
00054   proximity_threshold_(proximity_threshold)
00055 {}
00056 
00057 void FakeLoopClosureGenerator::initializeFromGraph (const pg::PoseGraph& g, const std::vector<pg::NodeId>& node_sequence)
00058 {
00059   ROS_ASSERT_MSG (false, "initializeFromGraph not implemented for fake loop closure (i.e., you can't use this constraint type when loading an existing graph from a file)");
00060 }
00061 
00062 void FakeLoopClosureGenerator::updateLocalization (const GraphLocalization& loc)
00063 {
00064   ROS_ASSERT_MSG(false, "Not implemented!");
00065 }
00066 
00067 NodeConstraintVector FakeLoopClosureGenerator::getConstraints (const pg::PoseGraph& graph, 
00068                                                                const pg::NodeId new_node, 
00069                                                                const NodePoseMap& optimized_poses)
00070 {
00071   NodeConstraintVector constraints;
00072   if (haveRecentlyReceivedPose()) {
00073     const gm::Pose& pose = last_pose_->pose;
00074     BOOST_FOREACH (const NodePoseMap::value_type entry, true_poses_) {
00075       const double dist = pg::euclideanDistance(entry.second.position, pose.position);
00076       if (dist<proximity_threshold_) {
00077         pg::PrecisionMatrix precision = Eigen3::MatrixXd::Identity(6,6);
00078         pg::PoseConstraint constraint = pg::makeConstraint(pg::relativeTransform(pose, entry.second),
00079                                                            pg::makePrecisionMatrix(1, 1, 1));
00080         for (unsigned i=0; i<6; i++) 
00081           constraint.precision(i,i)=10.0;
00082         constraints.push_back(NodeConstraint(entry.first, constraint));
00083         ROS_DEBUG_STREAM_NAMED ("fake_place_rec", "Adding constraint from " << entry.first << " to "
00084                                 << new_node << " : " << constraint);
00085       }
00086     }
00087     true_poses_[new_node] = last_pose_->pose;
00088   }
00089   else {
00090     ROS_DEBUG_NAMED ("fake_loop_closure", "Not adding constraint as no recent fake_localization received");
00091   }
00092   return constraints;
00093 }
00094 
00095 
00096 void FakeLoopClosureGenerator::locCB (const gm::PoseWithCovarianceStamped& msg)
00097 {
00098   gm::PoseStamped pose;
00099   pose.header = msg.header;
00100   pose.pose = msg.pose.pose;
00101   last_pose_ = pose;
00102 }
00103 
00104 bool FakeLoopClosureGenerator::haveRecentlyReceivedPose () const
00105 {
00106   const ros::Time cutoff = ros::Time::now() - ros::Duration(LOCALIZATION_RECENCY_THRESHOLD);
00107   return (last_pose_ && last_pose_->header.stamp > cutoff);
00108 }
00109 
00110 
00111 
00112 } // namespace graph_slam
00113 
00114 


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