Classes | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
swri::NodeHandle Class Reference

#include <node_handle.h>

Classes

struct  NodeHandleInternal
 

Public Member Functions

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)
 

Private Member Functions

ros::NodeHandle getDynamicParameterNodeHandle () const
 
std::string resolveName (const std::string &name) const
 
bool shouldAddParameter (const std::string &name) const
 

Private Attributes

std::string grouping_
 
std::string namespace_
 
boost::shared_ptr< NodeHandleInternalnh_
 

Friends

class DynamicParameters
 

Detailed Description

Definition at line 51 of file node_handle.h.

Constructor & Destructor Documentation

◆ NodeHandle() [1/2]

swri::NodeHandle::NodeHandle ( )
inline

Definition at line 112 of file node_handle.h.

◆ NodeHandle() [2/2]

swri::NodeHandle::NodeHandle ( ros::NodeHandle  nh,
ros::NodeHandle  pnh,
const std::string  description,
const char *  source_file = "" 
)
inline

Definition at line 117 of file node_handle.h.

Member Function Documentation

◆ advertise() [1/4]

template<typename M >
ros::Publisher swri::NodeHandle::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 = "" 
)
inline

Definition at line 1077 of file node_handle.h.

◆ advertise() [2/4]

template<typename M >
ros::Publisher swri::NodeHandle::advertise ( const std::string  name,
uint32_t  queue_size,
bool  latched,
const std::string  description 
)
inline

Definition at line 1016 of file node_handle.h.

◆ advertise() [3/4]

template<typename M >
ros::Publisher swri::NodeHandle::advertise ( const std::string  name,
uint32_t  queue_size,
const char *  description 
)
inline

Definition at line 1047 of file node_handle.h.

◆ advertise() [4/4]

ros::Publisher swri::NodeHandle::advertise ( ros::AdvertiseOptions ops,
const std::string &  description = "" 
)
inline

Definition at line 1112 of file node_handle.h.

◆ advertise_later()

template<class M >
void swri::NodeHandle::advertise_later ( const std::string &  name,
const std::string  description 
)
inline

Definition at line 790 of file node_handle.h.

◆ advertise_service_swri() [1/3]

template<class MReq , class MRes , class T >
swri::ServiceServer swri::NodeHandle::advertise_service_swri ( const std::string &  name,
bool(T::*)(const std::string &, const MReq &, MRes &)  srv_func,
T *  obj,
const std::string  description 
)
inline

Definition at line 990 of file node_handle.h.

◆ advertise_service_swri() [2/3]

template<class MReq , class MRes , class T >
swri::ServiceServer swri::NodeHandle::advertise_service_swri ( const std::string &  name,
bool(T::*)(MReq &, MRes &)  srv_func,
T *  obj,
const std::string  description 
)
inline

Definition at line 940 of file node_handle.h.

◆ advertise_service_swri() [3/3]

template<class MReq , class MRes , class T >
swri::ServiceServer swri::NodeHandle::advertise_service_swri ( const std::string &  name,
bool(T::*)(ros::ServiceEvent< MReq, MRes > &)  srv_func,
T *  obj,
const std::string  description 
)
inline

Definition at line 965 of file node_handle.h.

◆ advertiseService()

template<class MReq , class MRes , class T >
ros::ServiceServer swri::NodeHandle::advertiseService ( const std::string &  name,
bool(T::*)(MReq &, MRes &)  srv_func,
T *  obj,
const std::string  description 
)
inline

Definition at line 915 of file node_handle.h.

◆ createTimer()

template<class T >
ros::Timer swri::NodeHandle::createTimer ( ros::Duration  duration,
void(T::*)(const ros::TimerEvent &)  fp,
T *  obj,
const bool  oneshot = false,
const bool  autostart = true 
)
inline

Definition at line 1138 of file node_handle.h.

◆ createWallTimer()

template<class T >
ros::WallTimer swri::NodeHandle::createWallTimer ( ros::WallDuration  duration,
void(T::*)(const ros::WallTimerEvent &)  fp,
T *  obj,
const bool  oneshot = false,
const bool  autostart = true 
)
inline

Definition at line 1149 of file node_handle.h.

◆ getDocMsg()

marti_introspection_msgs::NodeInfo swri::NodeHandle::getDocMsg ( ) const
inline

Definition at line 165 of file node_handle.h.

◆ getDynamicParameterNodeHandle()

ros::NodeHandle swri::NodeHandle::getDynamicParameterNodeHandle ( ) const
inlineprivate

Definition at line 81 of file node_handle.h.

◆ getEnableDocs()

bool swri::NodeHandle::getEnableDocs ( ) const
inline

Definition at line 152 of file node_handle.h.

◆ getNodeHandle()

swri::NodeHandle swri::NodeHandle::getNodeHandle ( const std::string &  ns,
const std::string &  group = "" 
)
inline

Definition at line 178 of file node_handle.h.

◆ getParam() [1/3]

bool swri::NodeHandle::getParam ( const std::string &  name,
std::vector< std::string > &  value,
const std::string  description 
)
inline

Definition at line 232 of file node_handle.h.

◆ getParam() [2/3]

template<class T >
bool swri::NodeHandle::getParam ( const std::string &  name,
T &  value,
const std::string  description 
)
inline

Definition at line 204 of file node_handle.h.

◆ getParam() [3/3]

bool swri::NodeHandle::getParam ( const std::string &  name,
XmlRpc::XmlRpcValue value,
const std::string  description 
)
inline

Definition at line 210 of file node_handle.h.

◆ operator void *()

swri::NodeHandle::operator void * ( ) const
inline

Definition at line 149 of file node_handle.h.

◆ param() [1/5]

bool swri::NodeHandle::param ( const std::string &  name,
bool &  variable,
const bool  default_value,
const std::string  description,
const bool  dynamic = false 
)
inline

Definition at line 522 of file node_handle.h.

◆ param() [2/5]

bool swri::NodeHandle::param ( const std::string &  name,
double &  variable,
const double  default_value,
const std::string  description,
const bool  dynamic = false 
)
inline

Definition at line 262 of file node_handle.h.

◆ param() [3/5]

bool swri::NodeHandle::param ( const std::string &  name,
float &  variable,
const float  default_value,
const std::string  description,
const bool  dynamic = false 
)
inline

Definition at line 429 of file node_handle.h.

◆ param() [4/5]

bool swri::NodeHandle::param ( const std::string &  name,
int &  variable,
const int  default_value,
const std::string  description,
const bool  dynamic = false 
)
inline

Definition at line 460 of file node_handle.h.

◆ param() [5/5]

bool swri::NodeHandle::param ( const std::string &  name,
std::string &  variable,
const std::string  default_value,
const std::string  description,
const bool  dynamic = false 
)
inline

Definition at line 491 of file node_handle.h.

◆ ranged_param() [1/3]

bool swri::NodeHandle::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 
)
inline

Definition at line 294 of file node_handle.h.

◆ ranged_param() [2/3]

bool swri::NodeHandle::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 
)
inline

Definition at line 384 of file node_handle.h.

◆ ranged_param() [3/3]

bool swri::NodeHandle::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 
)
inline

Definition at line 339 of file node_handle.h.

◆ resolveName()

std::string swri::NodeHandle::resolveName ( const std::string &  name) const
inlineprivate

Definition at line 71 of file node_handle.h.

◆ serviceClient()

template<class T >
ros::ServiceClient swri::NodeHandle::serviceClient ( const std::string &  name,
const std::string &  description 
)
inline

Definition at line 891 of file node_handle.h.

◆ setParam()

template<class T >
void swri::NodeHandle::setParam ( const std::string &  name,
T &  value 
)
inline

Definition at line 255 of file node_handle.h.

◆ shouldAddParameter()

bool swri::NodeHandle::shouldAddParameter ( const std::string &  name) const
inlineprivate

Definition at line 93 of file node_handle.h.

◆ subscribe() [1/5]

template<class M >
ros::Subscriber swri::NodeHandle::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() 
)
inline

Definition at line 662 of file node_handle.h.

◆ subscribe() [2/5]

template<class M , class T >
ros::Subscriber swri::NodeHandle::subscribe ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &) const  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 635 of file node_handle.h.

◆ subscribe() [3/5]

template<class M , class T >
ros::Subscriber swri::NodeHandle::subscribe ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 608 of file node_handle.h.

◆ subscribe() [4/5]

template<class M , class T >
ros::Subscriber swri::NodeHandle::subscribe ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const ros::MessageEvent< M const > &) const  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 715 of file node_handle.h.

◆ subscribe() [5/5]

template<class M , class T >
ros::Subscriber swri::NodeHandle::subscribe ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const ros::MessageEvent< M const > &)  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 688 of file node_handle.h.

◆ subscribe_later()

template<class M >
void swri::NodeHandle::subscribe_later ( const std::string &  name,
const std::string  description 
)
inline

Definition at line 768 of file node_handle.h.

◆ subscribe_optional()

template<class M , class T >
swri::OptionalSubscriber swri::NodeHandle::subscribe_optional ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 811 of file node_handle.h.

◆ subscribe_swri() [1/3]

template<class M >
swri::Subscriber swri::NodeHandle::subscribe_swri ( const std::string &  name,
boost::shared_ptr< M const > *  dest,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 741 of file node_handle.h.

◆ subscribe_swri() [2/3]

template<class M >
swri::Subscriber swri::NodeHandle::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() 
)
inline

Definition at line 581 of file node_handle.h.

◆ subscribe_swri() [3/3]

template<class M , class T >
swri::Subscriber swri::NodeHandle::subscribe_swri ( const std::string &  name,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
T *  obj,
const std::string  description,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Definition at line 553 of file node_handle.h.

◆ topic_service_client()

template<class M >
swri::TopicServiceClient<M> swri::NodeHandle::topic_service_client ( const std::string &  name,
const std::string  description 
)
inline

Definition at line 838 of file node_handle.h.

◆ topic_service_server()

template<class MReq , class MRes , class T >
swri::TopicServiceServer swri::NodeHandle::topic_service_server ( const std::string &  name,
bool(T::*)(const MReq &, MRes &)  srv_func,
T *  obj,
const std::string  description 
)
inline

Definition at line 864 of file node_handle.h.

Friends And Related Function Documentation

◆ DynamicParameters

friend class DynamicParameters
friend

Definition at line 53 of file node_handle.h.

Member Data Documentation

◆ grouping_

std::string swri::NodeHandle::grouping_
private

Definition at line 68 of file node_handle.h.

◆ namespace_

std::string swri::NodeHandle::namespace_
private

Definition at line 67 of file node_handle.h.

◆ nh_

boost::shared_ptr<NodeHandleInternal> swri::NodeHandle::nh_
private

Definition at line 66 of file node_handle.h.


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


swri_roscpp
Author(s): P. J. Reed
autogenerated on Tue Oct 3 2023 02:32:28