#include <diff_publisher.h>
Public Member Functions | |
void | addDiff (pose_graph::PoseGraphDiff *diff) |
add the next diff Stamp diff with current id | |
DiffPublisher (const ros::NodeHandle &nh) | |
Constructor that initializes empty graph. | |
bool | getGraph (pose_graph::GetGraph::Request &req, pose_graph::GetGraph::Response &resp) |
Allow subscribers to request the entire graph. | |
void | setGraph (const pose_graph::PoseGraph &graph) |
Private Attributes | |
unsigned | current_id_ |
ros::Publisher | diff_pub_ |
pose_graph::PoseGraph | graph_ |
ros::ServiceServer | graph_srv_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
Definition at line 51 of file diff_publisher.h.
graph_slam::DiffPublisher::DiffPublisher | ( | const ros::NodeHandle & | nh | ) |
Constructor that initializes empty graph.
Definition at line 39 of file diff_publisher.cpp.
void graph_slam::DiffPublisher::addDiff | ( | pose_graph::PoseGraphDiff * | diff | ) |
add the next diff Stamp diff with current id
Definition at line 46 of file diff_publisher.cpp.
bool graph_slam::DiffPublisher::getGraph | ( | pose_graph::GetGraph::Request & | req, |
pose_graph::GetGraph::Response & | resp | ||
) |
Allow subscribers to request the entire graph.
Definition at line 54 of file diff_publisher.cpp.
void graph_slam::DiffPublisher::setGraph | ( | const pose_graph::PoseGraph & | 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 62 of file diff_publisher.cpp.
unsigned graph_slam::DiffPublisher::current_id_ [private] |
Definition at line 85 of file diff_publisher.h.
Definition at line 77 of file diff_publisher.h.
Definition at line 84 of file diff_publisher.h.
Definition at line 78 of file diff_publisher.h.
boost::mutex graph_slam::DiffPublisher::mutex_ [mutable, private] |
Definition at line 75 of file diff_publisher.h.
Definition at line 76 of file diff_publisher.h.