|
template<typename M > |
ros::Publisher | swri::advertise (swri::NodeHandle &nh, const std::string name, uint32_t queue_size, bool latched, const std::string description) |
|
template<typename M > |
ros::Publisher | swri::advertise (swri::NodeHandle &nh, const std::string name, uint32_t queue_size, const char *description) |
|
template<class MReq , class MRes , class T > |
swri::ServiceServer | swri::advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const std::string &, const MReq &, MRes &), T *obj, const std::string description) |
|
template<class MReq , class MRes , class T > |
swri::ServiceServer | swri::advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj, const std::string description) |
|
template<class MReq , class MRes , class T > |
swri::ServiceServer | swri::advertiseService (swri::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj, const std::string description) |
|
template<typename T > |
bool | swri::getParam (swri::NodeHandle &nh, const std::string name, T &value, const std::string description) |
|
void | swri::param (swri::NodeHandle &nh, const std::string name, std::string &value, const std::string def, const std::string description) |
|
template<typename T > |
void | swri::param (swri::NodeHandle &nh, const std::string name, T &value, const T def) |
|
template<typename T > |
void | swri::param (swri::NodeHandle &nh, const std::string name, T &value, const T def, const std::string description) |
|
void | swri::ranged_param (swri::NodeHandle &nh, const std::string name, double &value, const double def, const std::string description="", const double min=-std::numeric_limits< double >::infinity(), const double max=std::numeric_limits< double >::infinity()) |
|
template<typename T > |
void | swri::setParam (swri::NodeHandle &nh, const std::string &name, T &value) |
|
template<class M > |
swri::Subscriber | swri::subscribe (swri::NodeHandle &nh, const std::string &name, boost::shared_ptr< M const > *dest, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M , class T > |
swri::Subscriber | swri::subscribe (swri::NodeHandle &nh, const std::string &name, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
void | swri::timeoutParam (swri::NodeHandle &nh, swri::Subscriber &sub, const std::string name, const double timeout, const std::string desc) |
|