|
| ~NodeletBase () override=default |
|
| NodeletWithDiagnostics () |
|
virtual | ~NodeletWithDiagnostics () |
|
::cras::NodeletAwareTFBuffer & | getBuffer () const override |
| Get the TF buffer used by the nodelet. If none has been set by setBuffer() , a buffer is automatically created. More...
|
|
| NodeletWithSharedTfBuffer () |
|
void | setBuffer (const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override |
| Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is created. More...
|
|
bool | usesSharedBuffer () const override |
| Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically created. More...
|
|
virtual | ~NodeletWithSharedTfBuffer () |
|
| ~ThreadNameUpdatingNodelet () override |
|
| NodeletParamHelper () |
|
| ~NodeletParamHelper () override |
|
::cras::LogHelperPtr | getLogger () const |
| Return the log helper used for logging. More...
|
|
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr> |
ResultType | getParam (const ::cras::GetParamAdapter ¶m, 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...
|
|
template<typename ResultType , typename ParamServerType = typename ::cras::DefaultParamServerType<ResultType>::type, ::cras::check_get_param_types< ResultType, ParamServerType > * = nullptr> |
ResultType | getParam (const ::cras::GetParamAdapter ¶m, 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 ::std::string | getParam (const ::cras::GetParamAdapter ¶m, 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...
|
|
inline ::std::string | getParam (const ::cras::GetParamAdapter ¶m, 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 ¶m, 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...
|
|
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 ¶m, 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 ¶m, 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...
|
|
inline ::cras::GetParamResult<::std::string > | getParamVerbose (const ::cras::GetParamAdapter ¶m, 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...
|
|
| ParamHelper (const ::cras::LogHelperPtr &log) |
|
void | setLogger (const ::cras::LogHelperPtr &logger) |
| Set the log helper used for logging. More...
|
|
virtual | ~ParamHelper ()=default |
|
::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...
|
|
bool | ok () const override |
| Whether it is OK to continue sleeping. If false, a pending sleep() should stop as soon as possible. More...
|
|
void | requestStop () override |
| Call this function to request stopping this nodelet. ok() should return false after calling this. It terminates all ongoing sleeps called by this->sleep() . More...
|
|
void | shutdown () |
|
virtual | ~StatefulNodelet () |
|
| InterruptibleSleepInterface () |
|
virtual bool | sleep (const ::ros::Duration &duration) const |
| Sleep for the given duration or until ok() returns false. More...
|
|
virtual | ~InterruptibleSleepInterface () |
| Destroy the object waiting for a pending sleep() call to finish. More...
|
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (::ros::NodeHandle publisherNh, ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (const ::std::string &topic, size_t queueSize, bool latch=false) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > | advertiseDiagnosed (ros::AdvertiseOptions &options) |
| Advertise a topic and setup up an automatic topic diagnostic task for it. More...
|
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) |
|
| CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",)) |
|
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate) |
| Create a diagnosed publisher for a message type without header. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace, const ::ros::Rate &defaultRate) |
| Create a diagnosed publisher for a message type with header. More...
|
|
::std::unique_ptr<::cras::DiagnosedPublisher< T > > | createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string ¶mNamespace) |
| Create a diagnosed publisher for a message type with header. More...
|
|
::ros::NodeHandle | getDefaultDiagNh (const ::ros::NodeHandle &pubSubNh, const ::std::string &diagNamespace) |
| Get the default node handle for reading diagnostic task configuration. More...
|
|
::cras::BoundParamHelperPtr | getDiagParams (const ::ros::NodeHandle &nh, const ::std::string &diagNamespace, const ::std::string &topic) |
| Get the parameters configuring a diagnosed publisher or subscriber. More...
|
|
::cras::DiagnosticUpdater & | getDiagUpdater (bool forceNew=false) const |
| Get a diagnostic updater to be used with this nodelet. More...
|
|
void | startDiagTimer () const |
| Start periodic updates of the diagnostics updater. More...
|
|
void | startDiagTimer (const ::ros::NodeHandle &nh) const |
| Start periodic updates of the diagnostics updater. More...
|
|
void | stopDiagTimer () const |
| Stop the automatic updates of the diagnostic updater. More...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > | subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, 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...
|
|
void | updateThreadName () const |
| Set custom name of the current thread to this nodelet's name. More...
|
|
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
| 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...
|
|
ResultType | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
| 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 ::std::string | getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
| 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 ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
| 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< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
| 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< ResultType > | getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) |
| 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 ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
| 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 ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) |
| 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...
|
|
::cras::BoundParamHelperPtr | params (const ::ros::NodeHandle &node, const ::std::string &ns="") const |
| Creates a version of this param helper "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
|
|
::cras::BoundParamHelperPtr | paramsForNodeHandle (const ::ros::NodeHandle &node) const |
| Creates a version of this param helper "bound" to the given node handle, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
|
|
::cras::BoundParamHelperPtr | privateParams (const ::std::string &ns="") const |
| Creates a version of this param helper "bound" to the private nodelet parameters, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
|
|
::cras::BoundParamHelperPtr | publicParams (const ::std::string &ns="") const |
| Creates a version of this param helper "bound" to the public nodelet parameters, so that it is not needed to specify the node handle in the subsequent getParam() calls. More...
|
|
::cras::LogHelperPtr | log |
| Log helper. More...
|
|
::ros::WallDuration | pollDuration {0, 1000000} |
| How long to wait between querying the ok() status and other conditions. More...
|
|