#include <diff_subscriber.h>
Public Types | |
typedef boost::function< void(boost::optional < const graph_mapping_msgs::ConstraintGraphDiff & > , const ConstraintGraph &)> | DiffCallback |
Public Member Functions | |
DiffSubscriber (const DiffCallback &diff_cb) | |
Constructor starts with empty graph and sets up subscriptions. | |
ConstraintGraph | getCurrentGraph () const |
Return copy of current graph. | |
Private Member Functions | |
void | diffCB (const graph_mapping_msgs::ConstraintGraphDiff &diff) |
Subscription callback for diffs. | |
Private Attributes | |
DiffCallback | diff_callback_ |
ros::Subscriber | diff_sub_ |
ConstraintGraph | graph_ |
ros::ServiceClient | graph_client_ |
unsigned | last_id_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
Does the bookkeeping to subscribe to constraint 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. Threadsafe
Definition at line 58 of file diff_subscriber.h.
typedef boost::function<void (boost::optional<const graph_mapping_msgs::ConstraintGraphDiff&>, const ConstraintGraph&)> pose_graph::DiffSubscriber::DiffCallback |
Definition at line 63 of file diff_subscriber.h.
pose_graph::DiffSubscriber::DiffSubscriber | ( | const DiffCallback & | diff_cb | ) |
Constructor starts with empty graph and sets up subscriptions.
Definition at line 45 of file diff_subscriber.cpp.
void pose_graph::DiffSubscriber::diffCB | ( | const graph_mapping_msgs::ConstraintGraphDiff & | diff | ) | [private] |
Subscription callback for diffs.
ConstraintGraph pose_graph::DiffSubscriber::getCurrentGraph | ( | ) | const |
Return copy of current graph.
Definition at line 87 of file diff_subscriber.cpp.
Definition at line 82 of file diff_subscriber.h.
ros::Subscriber pose_graph::DiffSubscriber::diff_sub_ [private] |
Definition at line 83 of file diff_subscriber.h.
Definition at line 90 of file diff_subscriber.h.
ros::ServiceClient pose_graph::DiffSubscriber::graph_client_ [private] |
Definition at line 84 of file diff_subscriber.h.
unsigned pose_graph::DiffSubscriber::last_id_ [private] |
Definition at line 91 of file diff_subscriber.h.
boost::mutex pose_graph::DiffSubscriber::mutex_ [mutable, private] |
Definition at line 80 of file diff_subscriber.h.
ros::NodeHandle pose_graph::DiffSubscriber::nh_ [private] |
Definition at line 81 of file diff_subscriber.h.