pose_graph::DiffPublisher Class Reference

#include <diff_publisher.h>

List of all members.

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_

Detailed Description

Definition at line 48 of file diff_publisher.h.


Constructor & Destructor Documentation

pose_graph::DiffPublisher::DiffPublisher (  ) 

Constructor that initializes empty graph.

Definition at line 45 of file diff_publisher.cpp.


Member Function Documentation

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.


Member Data Documentation

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.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Defines


pose_graph
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:37:08 2013