pose_graph::CachedNodeMap< M > Class Template Reference

A map<unsigned, M::ConstPtr> backed by a warehouse collection. More...

#include <graph_db.h>

List of all members.

Public Member Functions

 CachedNodeMap (const CachedNodeMap &m)
 Copy constructor.
 CachedNodeMap (warehouse::Collection< M > *coll)
 Construct a CachedNodeMap from a Collection. The caller is responsible for the Collection object, which must stay alive as long as this object does.
 CachedNodeMap (warehouse::WarehouseClient *client, const std::string &name)
 Construct a CachedNode map from an existing WarehouseClient object. The caller is responsible for the WarehouseClient object, which must be alive as long as this object is.
M::ConstPtr get (unsigned n) const
 Get the message associated with this node. Calls out to the warehouse only if the message is not found in the cache.
bool hasData (unsigned n) const
 Does this node have associated node data? Calls out to the warehouse unless the data is present in the cache.
void set (unsigned n, const M &m)
 Set the message associated with this node and publish it to the warehouse. Remove any existing message.
void set (unsigned n, typename M::ConstPtr)
 Set the message associated with this node and publish it to the warehouse. Remove any existing message.

Private Member Functions

void initialLoad ()
 Load all messages initially present.
void removeExisting (unsigned n)
 Remove existing messages for a given node.
void updateCB (const warehouse::UpdateNotification &m)
 Callback when collection is updated.

Private Attributes

warehouse::Collection< M > * coll_
boost::shared_ptr
< warehouse::Collection< M > > 
coll_ptr_
bool initialized_
std::map< unsigned, typename
M::ConstPtr > 
map_
boost::mutex mutex_
ros::NodeHandle nh_
ros::Subscriber update_sub_

Detailed Description

template<class M>
class pose_graph::CachedNodeMap< M >

A map<unsigned, M::ConstPtr> backed by a warehouse collection.

Can have only one of these per collection per node

Definition at line 72 of file graph_db.h.


Constructor & Destructor Documentation

template<class M>
pose_graph::CachedNodeMap< M >::CachedNodeMap ( warehouse::WarehouseClient *  client,
const std::string &  name 
)

Construct a CachedNode map from an existing WarehouseClient object. The caller is responsible for the WarehouseClient object, which must be alive as long as this object is.

template<class M>
pose_graph::CachedNodeMap< M >::CachedNodeMap ( warehouse::Collection< M > *  coll  ) 

Construct a CachedNodeMap from a Collection. The caller is responsible for the Collection object, which must stay alive as long as this object does.

template<class M >
pose_graph::CachedNodeMap< M >::CachedNodeMap ( const CachedNodeMap< M > &  m  )  [inline]

Copy constructor.

Definition at line 125 of file graph_db_impl.h.


Member Function Documentation

template<class M >
M::ConstPtr pose_graph::CachedNodeMap< M >::get ( unsigned  n  )  const [inline]

Get the message associated with this node. Calls out to the warehouse only if the message is not found in the cache.

Exceptions:
DataNotFoundException 
WarehouseClientException 

Definition at line 161 of file graph_db_impl.h.

template<class M >
bool pose_graph::CachedNodeMap< M >::hasData ( unsigned  n  )  const [inline]

Does this node have associated node data? Calls out to the warehouse unless the data is present in the cache.

Definition at line 222 of file graph_db_impl.h.

template<class M >
void pose_graph::CachedNodeMap< M >::initialLoad (  )  [inline, private]

Load all messages initially present.

Definition at line 133 of file graph_db_impl.h.

template<class M >
void pose_graph::CachedNodeMap< M >::removeExisting ( unsigned  n  )  [inline, private]

Remove existing messages for a given node.

Definition at line 181 of file graph_db_impl.h.

template<class M >
void pose_graph::CachedNodeMap< M >::set ( unsigned  n,
const M &  m 
) [inline]

Set the message associated with this node and publish it to the warehouse. Remove any existing message.

Exceptions:
WarehouseClientException 
NodeDuplicateDataException 

Definition at line 212 of file graph_db_impl.h.

template<class M >
void pose_graph::CachedNodeMap< M >::set ( unsigned  n,
typename M::ConstPtr  msg 
) [inline]

Set the message associated with this node and publish it to the warehouse. Remove any existing message.

Exceptions:
WarehouseClientException 
NodeDuplicateDataException 

Definition at line 202 of file graph_db_impl.h.

template<class M>
void pose_graph::CachedNodeMap< M >::updateCB ( const warehouse::UpdateNotification &  m  )  [private]

Callback when collection is updated.


Member Data Documentation

template<class M>
warehouse::Collection<M>* pose_graph::CachedNodeMap< M >::coll_ [private]

Definition at line 130 of file graph_db.h.

template<class M>
boost::shared_ptr<warehouse::Collection<M> > pose_graph::CachedNodeMap< M >::coll_ptr_ [private]

Definition at line 129 of file graph_db.h.

template<class M>
bool pose_graph::CachedNodeMap< M >::initialized_ [private]

Definition at line 126 of file graph_db.h.

template<class M>
std::map<unsigned, typename M::ConstPtr> pose_graph::CachedNodeMap< M >::map_ [mutable, private]

Definition at line 133 of file graph_db.h.

template<class M>
boost::mutex pose_graph::CachedNodeMap< M >::mutex_ [mutable, private]

Definition at line 123 of file graph_db.h.

template<class M>
ros::NodeHandle pose_graph::CachedNodeMap< M >::nh_ [private]

Definition at line 135 of file graph_db.h.

template<class M>
ros::Subscriber pose_graph::CachedNodeMap< M >::update_sub_ [private]

Definition at line 138 of file graph_db.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