#include <diff_publisher.h>
Public Member Functions | |
void | addDiff (graph_mapping_msgs::ConstraintGraphDiff *diff) |
add the next diff Stamp diff with current id | |
DiffPublisher () | |
Constructor that initializes empty graph. | |
bool | getGraph (graph_mapping_msgs::GetGraph::Request &req, graph_mapping_msgs::GetGraph::Response &resp) |
Allow subscribers to request the entire graph. | |
void | setGraph (const ConstraintGraph &graph) |
Private Attributes | |
unsigned | current_id_ |
ros::Publisher | diff_pub_ |
ConstraintGraph | graph_ |
ros::ServiceServer | graph_srv_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
Definition at line 48 of file diff_publisher.h.
pose_graph::DiffPublisher::DiffPublisher | ( | ) |
Constructor that initializes empty graph.
Definition at line 45 of file diff_publisher.cpp.
void pose_graph::DiffPublisher::addDiff | ( | graph_mapping_msgs::ConstraintGraphDiff * | diff | ) |
add the next diff Stamp diff with current id
bool pose_graph::DiffPublisher::getGraph | ( | graph_mapping_msgs::GetGraph::Request & | req, | |
graph_mapping_msgs::GetGraph::Response & | resp | |||
) |
Allow subscribers to request the entire graph.
void pose_graph::DiffPublisher::setGraph | ( | const ConstraintGraph & | graph | ) |
Reset the entire graph; this will trigger all subscribers requesting a new full graph Caller responsible for making sure this isn't interleaved with a call to addDiff
Definition at line 68 of file diff_publisher.cpp.
unsigned pose_graph::DiffPublisher::current_id_ [private] |
Definition at line 79 of file diff_publisher.h.
ros::Publisher pose_graph::DiffPublisher::diff_pub_ [private] |
Definition at line 71 of file diff_publisher.h.
Definition at line 78 of file diff_publisher.h.
ros::ServiceServer pose_graph::DiffPublisher::graph_srv_ [private] |
Definition at line 72 of file diff_publisher.h.
boost::mutex pose_graph::DiffPublisher::mutex_ [mutable, private] |
Definition at line 69 of file diff_publisher.h.
ros::NodeHandle pose_graph::DiffPublisher::nh_ [private] |
Definition at line 70 of file diff_publisher.h.