Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate > Class Template Reference

#include <nav_grid_subscriber.h>

Public Types

using NewDataCallback = std::function< void(const nav_core2::UIntBounds &)>
 

Public Member Functions

void activate ()
 
void deactivate ()
 
 GenericNavGridSubscriber (nav_grid::NavGrid< NumericType > &data)
 
bool hasData () const
 
void init (ros::NodeHandle &nh, NewDataCallback callback, const std::string &topic="map", bool nav_grid=true, bool subscribe_to_updates=true)
 
void setCostInterpretation (const std::vector< NumericType > &cost_interpretation_table)
 

Protected Member Functions

void incomingNav (const NavGridOfX &new_map)
 
void incomingNavUpdate (const NavGridOfXUpdate &update)
 
void incomingOcc (const nav_msgs::OccupancyGridConstPtr &new_map)
 
void incomingOccUpdate (const map_msgs::OccupancyGridUpdateConstPtr &update)
 

Protected Attributes

NewDataCallback callback_
 
std::vector< NumericType > cost_interpretation_table_
 
nav_grid::NavGrid< NumericType > & data_
 
bool map_received_
 
bool nav_grid_
 
ros::NodeHandle nh_
 
ros::Subscriber sub_
 
bool subscribe_to_updates_
 
std::string topic_
 
ros::Subscriber update_sub_
 

Detailed Description

template<typename NumericType, typename NavGridOfX, typename NavGridOfXUpdate>
class nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >

Definition at line 56 of file nav_grid_subscriber.h.

Member Typedef Documentation

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
using nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::NewDataCallback = std::function<void(const nav_core2::UIntBounds&)>

Definition at line 59 of file nav_grid_subscriber.h.

Constructor & Destructor Documentation

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::GenericNavGridSubscriber ( nav_grid::NavGrid< NumericType > &  data)
inlineexplicit

Definition at line 61 of file nav_grid_subscriber.h.

Member Function Documentation

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::activate ( )
inline

Definition at line 73 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::deactivate ( )
inline

Definition at line 97 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
bool nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::hasData ( ) const
inline

Definition at line 103 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::incomingNav ( const NavGridOfX &  new_map)
inlineprotected

Definition at line 110 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::incomingNavUpdate ( const NavGridOfXUpdate &  update)
inlineprotected

Definition at line 117 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::incomingOcc ( const nav_msgs::OccupancyGridConstPtr &  new_map)
inlineprotected

Definition at line 127 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::incomingOccUpdate ( const map_msgs::OccupancyGridUpdateConstPtr &  update)
inlineprotected

Definition at line 138 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::init ( ros::NodeHandle nh,
NewDataCallback  callback,
const std::string &  topic = "map",
bool  nav_grid = true,
bool  subscribe_to_updates = true 
)
inline

Definition at line 62 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
void nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::setCostInterpretation ( const std::vector< NumericType > &  cost_interpretation_table)
inline

Definition at line 105 of file nav_grid_subscriber.h.

Member Data Documentation

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
NewDataCallback nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::callback_
protected

Definition at line 145 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
std::vector<NumericType> nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::cost_interpretation_table_
protected

Definition at line 147 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
nav_grid::NavGrid<NumericType>& nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::data_
protected

Definition at line 144 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
bool nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::map_received_
protected

Definition at line 150 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
bool nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::nav_grid_
protected

Definition at line 154 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
ros::NodeHandle nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::nh_
protected

Definition at line 152 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
ros::Subscriber nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::sub_
protected

Definition at line 149 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
bool nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::subscribe_to_updates_
protected

Definition at line 154 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
std::string nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::topic_
protected

Definition at line 153 of file nav_grid_subscriber.h.

template<typename NumericType , typename NavGridOfX , typename NavGridOfXUpdate >
ros::Subscriber nav_grid_pub_sub::GenericNavGridSubscriber< NumericType, NavGridOfX, NavGridOfXUpdate >::update_sub_
protected

Definition at line 149 of file nav_grid_subscriber.h.


The documentation for this class was generated from the following file:


nav_grid_pub_sub
Author(s):
autogenerated on Sun Jan 10 2021 04:08:50