#include <diff_subscriber.h>
Public Types | |
typedef boost::function< void(boost::optional < const pose_graph::PoseGraphDiff & > , const pose_graph::PoseGraph &)> | DiffCallback |
Public Member Functions | |
DiffSubscriber (const ros::NodeHandle &nh, const DiffCallback &diff_cb) | |
Constructor starts with empty graph and sets up subscriptions. | |
pose_graph::PoseGraph | getCurrentGraph () const |
Return copy of current graph. | |
Private Member Functions | |
void | diffCB (const pose_graph::PoseGraphDiff &diff) |
Subscription callback for diffs. | |
Private Attributes | |
DiffCallback | diff_callback_ |
ros::Subscriber | diff_sub_ |
pose_graph::PoseGraph | graph_ |
ros::ServiceClient | graph_client_ |
unsigned | last_id_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
Does the bookkeeping to subscribe to pose graph diffs It uses an id field to detect if it has dropped a diff. If so, it calls the get_graph service to re-request the entire graph. Calls a supplied callback with the diff (or uninitialized if this was a full graph) and full graph each time a diff is received.
Definition at line 55 of file diff_subscriber.h.
typedef boost::function<void (boost::optional<const pose_graph::PoseGraphDiff&>, const pose_graph::PoseGraph&)> graph_slam::DiffSubscriber::DiffCallback |
Definition at line 59 of file diff_subscriber.h.
graph_slam::DiffSubscriber::DiffSubscriber | ( | const ros::NodeHandle & | nh, |
const DiffCallback & | diff_cb | ||
) |
Constructor starts with empty graph and sets up subscriptions.
Definition at line 41 of file diff_subscriber.cpp.
void graph_slam::DiffSubscriber::diffCB | ( | const pose_graph::PoseGraphDiff & | diff | ) | [private] |
Subscription callback for diffs.
Definition at line 57 of file diff_subscriber.cpp.
Return copy of current graph.
Definition at line 77 of file diff_subscriber.cpp.
Definition at line 78 of file diff_subscriber.h.
Definition at line 79 of file diff_subscriber.h.
Definition at line 86 of file diff_subscriber.h.
Definition at line 80 of file diff_subscriber.h.
unsigned graph_slam::DiffSubscriber::last_id_ [private] |
Definition at line 87 of file diff_subscriber.h.
boost::mutex graph_slam::DiffSubscriber::mutex_ [mutable, private] |
Definition at line 76 of file diff_subscriber.h.
Definition at line 77 of file diff_subscriber.h.