Public Member Functions | List of all members
cras::NodeHandle Class Reference

#include <node_handle.h>

Inheritance diagram for cras::NodeHandle:
Inheritance graph
[legend]

Public Member Functions

 NodeHandle (const ::ros::NodeHandle &parent, const ::std::string &ns)
 
 NodeHandle (const ::ros::NodeHandle &parent, const ::std::string &ns, const ::ros::M_string &remappings)
 
 NodeHandle (const ::std::string &ns="", const ::ros::M_string &remappings={})
 
- Public Member Functions inherited from cras::NodeHandleWithDiagnostics
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, ::ros::AdvertiseOptions &options)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch=false)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch=false)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
template<class Message >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, const size_t queueSize, const bool latch=false)
 Advertise publication of a message, automatically adding diagnostics to it. More...
 
 NodeHandleWithDiagnostics (const ::ros::NodeHandle &parent, const ::std::string &ns)
 Create the node handle using the passed ROS node handle parameters. More...
 
 NodeHandleWithDiagnostics (const ::ros::NodeHandle &parent, const ::std::string &ns, const ::ros::M_string &remappings)
 Create the node handle using the passed ROS node handle parameters. More...
 
 NodeHandleWithDiagnostics (const ::std::string &ns="", const ::ros::M_string &remappings={})
 Create the node handle using the passed ROS node handle parameters. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, ::ros::SubscribeOptions &options)
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename C , typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename C , typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename C , typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
- Public Member Functions inherited from cras::NodeParamHelper
 NodeParamHelper (const ::ros::NodeHandle &parent, const ::std::string &ns)
 
 NodeParamHelper (const ::ros::NodeHandle &parent, const ::std::string &ns, const ::ros::M_string &remappings)
 
 NodeParamHelper (const ::std::string &ns="", const ::ros::M_string &remappings={})
 
- Public Member Functions inherited from ros::NodeHandle
Publisher advertise (AdvertiseOptions &ops)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, bool latch=false)
 
Publisher advertise (const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const VoidConstPtr &tracked_object=VoidConstPtr(), bool latch=false)
 
ServiceServer advertiseService (AdvertiseServiceOptions &ops)
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(MReq &, MRes &))
 
ServiceServer advertiseService (const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
 
ServiceServer advertiseService (const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
ServiceServer advertiseService (const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
 
SteadyTimer createSteadyTimer (SteadyTimerOptions &ops) const
 
SteadyTimer createSteadyTimer (WallDuration period, const SteadyTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
SteadyTimer createSteadyTimer (WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &) const, T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Duration period, void(T::*callback)(const TimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
 
Timer createTimer (TimerOptions &ops) const
 
WallTimer createWallTimer (WallDuration period, const WallTimerCallback &callback, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), const boost::shared_ptr< T > &obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
 
WallTimer createWallTimer (WallTimerOptions &ops) const
 
bool deleteParam (const std::string &key) const
 
CallbackQueueInterfacegetCallbackQueue () const
 
const std::string & getNamespace () const
 
bool getParam (const std::string &key, bool &b) const
 
bool getParam (const std::string &key, double &d) const
 
bool getParam (const std::string &key, float &f) const
 
bool getParam (const std::string &key, int &i) const
 
bool getParam (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParam (const std::string &key, std::map< std::string, double > &map) const
 
bool getParam (const std::string &key, std::map< std::string, float > &map) const
 
bool getParam (const std::string &key, std::map< std::string, int > &map) const
 
bool getParam (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParam (const std::string &key, std::string &s) const
 
bool getParam (const std::string &key, std::vector< bool > &vec) const
 
bool getParam (const std::string &key, std::vector< double > &vec) const
 
bool getParam (const std::string &key, std::vector< float > &vec) const
 
bool getParam (const std::string &key, std::vector< int > &vec) const
 
bool getParam (const std::string &key, std::vector< std::string > &vec) const
 
bool getParam (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamCached (const std::string &key, bool &b) const
 
bool getParamCached (const std::string &key, double &d) const
 
bool getParamCached (const std::string &key, float &f) const
 
bool getParamCached (const std::string &key, int &i) const
 
bool getParamCached (const std::string &key, std::map< std::string, bool > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, double > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, float > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, int > &map) const
 
bool getParamCached (const std::string &key, std::map< std::string, std::string > &map) const
 
bool getParamCached (const std::string &key, std::string &s) const
 
bool getParamCached (const std::string &key, std::vector< bool > &vec) const
 
bool getParamCached (const std::string &key, std::vector< double > &vec) const
 
bool getParamCached (const std::string &key, std::vector< float > &vec) const
 
bool getParamCached (const std::string &key, std::vector< int > &vec) const
 
bool getParamCached (const std::string &key, std::vector< std::string > &vec) const
 
bool getParamCached (const std::string &key, XmlRpc::XmlRpcValue &v) const
 
bool getParamNames (std::vector< std::string > &keys) const
 
const std::string & getUnresolvedNamespace () const
 
bool hasParam (const std::string &key) const
 
 NodeHandle (const NodeHandle &parent, const std::string &ns)
 
 NodeHandle (const NodeHandle &parent, const std::string &ns, const M_string &remappings)
 
 NodeHandle (const NodeHandle &rhs)
 
 NodeHandle (const std::string &ns=std::string(), const M_string &remappings=M_string())
 
bool ok () const
 
NodeHandleoperator= (const NodeHandle &rhs)
 
param (const std::string &param_name, const T &default_val) const
 
bool param (const std::string &param_name, T &param_val, const T &default_val) const
 
std::string resolveName (const std::string &name, bool remap=true) const
 
bool searchParam (const std::string &key, std::string &result) const
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
 
ServiceClient serviceClient (ServiceClientOptions &ops)
 
void setCallbackQueue (CallbackQueueInterface *queue)
 
void setParam (const std::string &key, bool b) const
 
void setParam (const std::string &key, const char *s) const
 
void setParam (const std::string &key, const std::map< std::string, bool > &map) const
 
void setParam (const std::string &key, const std::map< std::string, double > &map) const
 
void setParam (const std::string &key, const std::map< std::string, float > &map) const
 
void setParam (const std::string &key, const std::map< std::string, int > &map) const
 
void setParam (const std::string &key, const std::map< std::string, std::string > &map) const
 
void setParam (const std::string &key, const std::string &s) const
 
void setParam (const std::string &key, const std::vector< bool > &vec) const
 
void setParam (const std::string &key, const std::vector< double > &vec) const
 
void setParam (const std::string &key, const std::vector< float > &vec) const
 
void setParam (const std::string &key, const std::vector< int > &vec) const
 
void setParam (const std::string &key, const std::vector< std::string > &vec) const
 
void setParam (const std::string &key, const XmlRpc::XmlRpcValue &v) const
 
void setParam (const std::string &key, double d) const
 
void setParam (const std::string &key, int i) const
 
void shutdown ()
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
 
Subscriber subscribe (SubscribeOptions &ops)
 
 ~NodeHandle ()
 
- Public Member Functions inherited from cras::BoundParamHelper
 BoundParamHelper (const ::cras::LogHelperPtr &log, const ::cras::GetParamAdapterPtr &param)
 
inline ::std::string getNamespace () const
 Return the namespace this helper operates in. More...
 
inline ::std::string getParam (const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string getParam (const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions< std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult< std::string > getParamVerbose (const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
bool hasParam (const ::std::string &name, const bool searchNested=true) const
 Whether a parameter with the given name exists. More...
 
inline ::cras::BoundParamHelperPtr paramsInNamespace (const ::std::string &ns) const
 Return a parameter helper of a sub-namespace. More...
 
 ~BoundParamHelper () override=default
 

Additional Inherited Members

- Protected Member Functions inherited from cras::NodeHandleWithDiagnostics
virtual ::cras::BoundParamHelperPtr getDiagParams (const ::std::string &diagNs, const ::std::string &topic) const
 Get the param helper from which parameters for the diagnostic task can be extracted. More...
 
virtual ::std::string prefixDiagNamespace (const ::std::string &ns) const
 Optionally add a private node namespace to the given topic if this nodehandle is in the root node namespace. More...
 
- Protected Member Functions inherited from cras::ParamHelper
::cras::LogHelperPtr getLogger () const
 Return the log helper used for logging. More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value (if not nullopt), and print out a ROS log message with the loaded values (if specified). More...
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr>
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 Get the value of the given ROS parameter, falling back to the specified default value, and print out a ROS log message with the loaded values (if specified). More...
 
 ParamHelper (const ::cras::LogHelperPtr &log)
 
void setLogger (const ::cras::LogHelperPtr &logger)
 Set the log helper used for logging. More...
 
virtual ~ParamHelper ()=default
 
- Protected Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 This is the function picked up by CRAS_* logging macros. More...
 
 HasLogger (const ::cras::LogHelperPtr &log)
 Associate the logger with this interface. More...
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 Set the logger to be used for logging. More...
 
- Protected Attributes inherited from cras::NodeHandleWithDiagnostics
::ros::NodeHandle parentNh {}
 The parent node handle of this one. More...
 
- Protected Attributes inherited from cras::BoundParamHelper
::cras::GetParamAdapterPtr param
 The bound parameter adapter. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 Log helper. More...
 

Detailed Description

Definition at line 21 of file node_handle.h.

Constructor & Destructor Documentation

◆ NodeHandle() [1/3]

cras::NodeHandle::NodeHandle ( const ::std::string &  ns = "",
const ::ros::M_string remappings = {} 
)
inlineexplicit

Definition at line 24 of file node_handle.h.

◆ NodeHandle() [2/3]

cras::NodeHandle::NodeHandle ( const ::ros::NodeHandle parent,
const ::std::string &  ns 
)
inline

Definition at line 29 of file node_handle.h.

◆ NodeHandle() [3/3]

cras::NodeHandle::NodeHandle ( const ::ros::NodeHandle parent,
const ::std::string &  ns,
const ::ros::M_string remappings 
)
inline

Definition at line 34 of file node_handle.h.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:14