Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
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 }
00113
00114