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 () |
| int | getCompat () |
| std::string | getSimplifiedNamespace (ros::NodeHandle &nh) |
| STATIC_ASSERT (supported_level<=current_level &¤t_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, 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()) |
| 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()) |
Variables | |
| const int | current_level = 1 |
| const int | default_level = supported_level |
| const int | supported_level = 0 |
| ros::Publisher 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 176 of file compatibility.h.
| ros::ServiceServer 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 200 of file compatibility.h.
| void compat::checkCompatMode | ( | ) |
Definition at line 60 of file compatibility.h.
| int compat::getCompat | ( | ) |
Definition at line 53 of file compatibility.h.
| std::string compat::getSimplifiedNamespace | ( | ros::NodeHandle & | nh | ) |
Definition at line 89 of file compatibility.h.
| compat::STATIC_ASSERT | ( | supported_level<=current_level &¤t_level<=supported_level+ | 1 | ) |
| compat::STATIC_ASSERT | ( | supported_level<=default_level &&default_level<= | current_level | ) |
| ros::Subscriber 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 150 of file compatibility.h.
| ros::Subscriber 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 98 of file compatibility.h.
| const int compat::current_level = 1 |
Definition at line 46 of file compatibility.h.
| const int compat::default_level = supported_level |
Definition at line 48 of file compatibility.h.
| const int compat::supported_level = 0 |
Definition at line 47 of file compatibility.h.