|
template<typename M > |
ros::Publisher | advertise (const std::string &topic, uint32_t queue_size, const ros::SubscriberStatusCallback &connect_cb, const ros::SubscriberStatusCallback &disconnect_cb=ros::SubscriberStatusCallback(), const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), bool latch=false, const std::string &description="") |
|
template<typename M > |
ros::Publisher | advertise (const std::string name, uint32_t queue_size, bool latched, const std::string description) |
|
template<typename M > |
ros::Publisher | advertise (const std::string name, uint32_t queue_size, const char *description) |
|
ros::Publisher | advertise (ros::AdvertiseOptions &ops, const std::string &description="") |
|
template<class M > |
void | advertise_later (const std::string &name, const std::string description) |
|
template<class MReq , class MRes , class T > |
swri::ServiceServer | advertise_service_swri (const std::string &name, 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 | advertise_service_swri (const std::string &name, bool(T::*srv_func)(MReq &, MRes &), T *obj, const std::string description) |
|
template<class MReq , class MRes , class T > |
swri::ServiceServer | advertise_service_swri (const std::string &name, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj, const std::string description) |
|
template<class MReq , class MRes , class T > |
ros::ServiceServer | advertiseService (const std::string &name, bool(T::*srv_func)(MReq &, MRes &), T *obj, const std::string description) |
|
template<class T > |
ros::Timer | createTimer (ros::Duration duration, void(T::*fp)(const ros::TimerEvent &), T *obj, const bool oneshot=false, const bool autostart=true) |
|
template<class T > |
ros::WallTimer | createWallTimer (ros::WallDuration duration, void(T::*fp)(const ros::WallTimerEvent &), T *obj, const bool oneshot=false, const bool autostart=true) |
|
marti_introspection_msgs::NodeInfo | getDocMsg () const |
|
bool | getEnableDocs () const |
|
swri::NodeHandle | getNodeHandle (const std::string &ns, const std::string &group="") |
|
bool | getParam (const std::string &name, std::vector< std::string > &value, const std::string description) |
|
template<class T > |
bool | getParam (const std::string &name, T &value, const std::string description) |
|
bool | getParam (const std::string &name, XmlRpc::XmlRpcValue &value, const std::string description) |
|
| NodeHandle () |
|
| NodeHandle (ros::NodeHandle nh, ros::NodeHandle pnh, const std::string description, const char *source_file="") |
|
| operator void * () const |
|
bool | param (const std::string &name, bool &variable, const bool default_value, const std::string description, const bool dynamic=false) |
|
bool | param (const std::string &name, double &variable, const double default_value, const std::string description, const bool dynamic=false) |
|
bool | param (const std::string &name, float &variable, const float default_value, const std::string description, const bool dynamic=false) |
|
bool | param (const std::string &name, int &variable, const int default_value, const std::string description, const bool dynamic=false) |
|
bool | param (const std::string &name, std::string &variable, const std::string default_value, const std::string description, const bool dynamic=false) |
|
bool | ranged_param (const std::string &name, double &variable, const double default_value, const std::string description, const double min_value=0.0, const double max_value=0.0, const bool dynamic=false) |
|
bool | ranged_param (const std::string &name, float &variable, const float default_value, const std::string description, const float min_value=0.0, const float max_value=0.0, const bool dynamic=false) |
|
bool | ranged_param (const std::string &name, int &variable, const int default_value, const std::string description, const int min_value=0.0, const int max_value=0.0, const bool dynamic=false) |
|
template<class T > |
ros::ServiceClient | serviceClient (const std::string &name, const std::string &description) |
|
template<class T > |
void | setParam (const std::string &name, T &value) |
|
template<class M > |
ros::Subscriber | subscribe (const std::string &name, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M , class T > |
ros::Subscriber | subscribe (const std::string &name, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M , class T > |
ros::Subscriber | subscribe (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()) |
|
template<class M , class T > |
ros::Subscriber | subscribe (const std::string &name, uint32_t queue_size, void(T::*fp)(const ros::MessageEvent< M const > &) const, T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M , class T > |
ros::Subscriber | subscribe (const std::string &name, uint32_t queue_size, void(T::*fp)(const ros::MessageEvent< M const > &), T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M > |
void | subscribe_later (const std::string &name, const std::string description) |
|
template<class M , class T > |
swri::OptionalSubscriber | subscribe_optional (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()) |
|
template<class M > |
swri::Subscriber | subscribe_swri (const std::string &name, boost::shared_ptr< M const > *dest, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M > |
swri::Subscriber | subscribe_swri (const std::string &name, uint32_t queue_size, boost::function< void(const boost::shared_ptr< M const > &)> fp, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints()) |
|
template<class M , class T > |
swri::Subscriber | subscribe_swri (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()) |
|
template<class M > |
swri::TopicServiceClient< M > | topic_service_client (const std::string &name, const std::string description) |
|
template<class MReq , class MRes , class T > |
swri::TopicServiceServer | topic_service_server (const std::string &name, bool(T::*srv_func)(const MReq &, MRes &), T *obj, const std::string description) |
|