diff_subscriber.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 #include <graph_slam/diff_subscriber.h>
00032 #include <pose_graph/pose_graph_message.h>
00033 #include <pose_graph/GetGraph.h>
00034 #include <boost/thread.hpp>
00035 
00036 namespace graph_slam
00037 {
00038 
00039 using namespace pose_graph;
00040 
00041 DiffSubscriber::DiffSubscriber (const ros::NodeHandle& nh, const DiffSubscriber::DiffCallback& cb) :
00042   nh_(nh), diff_callback_(cb),
00043   graph_client_(nh_.serviceClient<GetGraph>("get_graph")), last_id_(0)
00044 {
00045   // We don't want to wait till the first diff is sent.  So we invoke our own callback
00046   // with a fake diff to trigger a service call.  Note that it's fine if 
00047   
00048   PoseGraphDiff fake_diff;
00049   fake_diff.id = 42; // Anything but 1
00050   diffCB(fake_diff);
00051   
00052   // Now that the current graph is received, subscribe to the true diff topic
00053   diff_sub_ = nh_.subscribe("graph_diffs", 10, &DiffSubscriber::diffCB, this);
00054 }
00055 
00056 
00057 void DiffSubscriber::diffCB (const PoseGraphDiff& diff)
00058 {
00059   boost::mutex::scoped_lock l(mutex_);
00060   boost::optional<const PoseGraphDiff&> possible_diff;
00061   if (diff.id == last_id_+1) {
00062     applyDiff(&graph_, diff);
00063     possible_diff = diff;
00064     last_id_ = diff.id;
00065   }
00066   else {
00067     ROS_INFO_STREAM ("Received diff with id " << diff.id << " while last id is " << last_id_);
00068     GetGraph srv;
00069     graph_client_.call(srv);
00070     graph_ = poseGraphFromRos(srv.response.graph);
00071     last_id_ = srv.response.id;
00072     ROS_INFO_STREAM ("New graph has id " << last_id_);
00073   }
00074   diff_callback_(possible_diff, graph_);
00075 }
00076 
00077 PoseGraph DiffSubscriber::getCurrentGraph () const
00078 {
00079   boost::mutex::scoped_lock l(mutex_);
00080   return graph_;
00081 }
00082 
00083 
00084 
00085 
00086 } // namespace


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