Functions | Variables
neonavigation_common::compat Namespace Reference

Functions

template<class M >
ros::Publisher advertise (ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, bool latch=false)
template<class T , class MReq , class MRes >
ros::ServiceServer advertiseService (ros::NodeHandle &nh_new, const std::string &service_new, ros::NodeHandle &nh_old, const std::string &service_old, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void checkCompatMode ()
template<typename T >
void deprecatedParam (const ros::NodeHandle &nh, const std::string &key, T &param, const T &default_value)
int getCompat ()
std::string getSimplifiedNamespace (ros::NodeHandle &nh)
 STATIC_ASSERT (supported_level<=current_level &&current_level<=supported_level+1)
 STATIC_ASSERT (supported_level<=default_level &&default_level<=current_level)
template<class M >
ros::Subscriber subscribe (ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
template<class M , class T >
ros::Subscriber subscribe (ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const ros::TransportHints &transport_hints=ros::TransportHints())
template<class M >
ros::Subscriber subscribe (ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), const ros::TransportHints &transport_hints=ros::TransportHints())

Variables

const int current_level = 1
const int default_level = supported_level
const int supported_level = 0

Function Documentation

template<class M >
ros::Publisher neonavigation_common::compat::advertise ( ros::NodeHandle nh_new,
const std::string &  topic_new,
ros::NodeHandle nh_old,
const std::string &  topic_old,
uint32_t  queue_size,
bool  latch = false 
)

Definition at line 203 of file compatibility.h.

template<class T , class MReq , class MRes >
ros::ServiceServer neonavigation_common::compat::advertiseService ( ros::NodeHandle nh_new,
const std::string &  service_new,
ros::NodeHandle nh_old,
const std::string &  service_old,
bool(T::*)(MReq &, MRes &)  srv_func,
T *  obj 
)

Definition at line 227 of file compatibility.h.

Definition at line 62 of file compatibility.h.

template<typename T >
void neonavigation_common::compat::deprecatedParam ( const ros::NodeHandle nh,
const std::string &  key,
T &  param,
const T &  default_value 
)

Definition at line 252 of file compatibility.h.

Definition at line 55 of file compatibility.h.

Definition at line 91 of file compatibility.h.

neonavigation_common::compat::STATIC_ASSERT ( supported_level<=current_level &&current_level<=supported_level+  1)
neonavigation_common::compat::STATIC_ASSERT ( supported_level<=default_level &&default_level<=  current_level)
template<class M >
ros::Subscriber neonavigation_common::compat::subscribe ( ros::NodeHandle nh_new,
const std::string &  topic_new,
ros::NodeHandle nh_old,
const std::string &  topic_old,
uint32_t  queue_size,
void(*)(M)  fp,
const ros::TransportHints transport_hints = ros::TransportHints() 
)

Definition at line 100 of file compatibility.h.

template<class M , class T >
ros::Subscriber neonavigation_common::compat::subscribe ( ros::NodeHandle nh_new,
const std::string &  topic_new,
ros::NodeHandle nh_old,
const std::string &  topic_old,
uint32_t  queue_size,
void(T::*)(M) const  fp,
T *  obj,
const ros::TransportHints transport_hints = ros::TransportHints() 
)

Definition at line 125 of file compatibility.h.

template<class M >
ros::Subscriber neonavigation_common::compat::subscribe ( ros::NodeHandle nh_new,
const std::string &  topic_new,
ros::NodeHandle nh_old,
const std::string &  topic_old,
uint32_t  queue_size,
const boost::function< void(const boost::shared_ptr< M const > &)> &  callback,
const ros::VoidConstPtr tracked_object = ros::VoidConstPtr(),
const ros::TransportHints transport_hints = ros::TransportHints() 
)

Definition at line 177 of file compatibility.h.


Variable Documentation

Definition at line 48 of file compatibility.h.

Definition at line 50 of file compatibility.h.

Definition at line 49 of file compatibility.h.



neonavigation_common
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:10