Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_topic_tools::DiagnosticNodelet Class Reference

Nodelet class based on ConnectionBasedNodelet and publish diagnostic infromation periodicaly. More...

#include <diagnostic_nodelet.h>

Inheritance diagram for jsk_topic_tools::DiagnosticNodelet:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< DiagnosticNodeletPtr
 

Public Member Functions

 DiagnosticNodelet (const std::string &name)
 Constructor and subclass need to call this. More...
 
- Public Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
 ConnectionBasedNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

virtual void onInit ()
 Initialize method. Subclass should call this method in its onInit method. More...
 
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 Method which is called periodically. More...
 
- Protected Member Functions inherited from jsk_topic_tools::ConnectionBasedNodelet
template<class T >
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size)
 Advertise a topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter. More...
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
 
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 Advertise an image topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and it and publish topic with appropriate latch parameter. More...
 
virtual void cameraConnectionBaseCallback ()
 callback function which is called when new subscriber come for camera image publisher or camera info publisher. This function is called from cameraConnectionCallback or cameraInfoConnectionCallback. More...
 
virtual void cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for camera image publisher More...
 
virtual void cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for camera info publisher More...
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come More...
 
virtual void imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for image publisher More...
 
virtual bool isSubscribed ()
 Returns true when this nodelet subscribes topics, false otherwise. More...
 
virtual void onInitPostProcess ()
 Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature. More...
 
virtual void subscribe ()=0
 This method is called when publisher is subscribed by other nodes. Set up subscribers in this method. More...
 
virtual void unsubscribe ()=0
 This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. More...
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 callback function which is called when walltimer duration run out. More...
 
virtual void warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event)
 callback function which is called when walltimer duration run out. More...
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

TimeredDiagnosticUpdater::Ptr diagnostic_updater_
 Pointer to TimeredDiagnosticUpdater to call updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper&) periodically. More...
 
const std::string name_
 Name of subclass. It is set by constructor and used as Diagnostic method. More...
 
jsk_topic_tools::VitalChecker::Ptr vital_checker_
 VitalChecker object wihch is used in default configuration. More...
 
- Protected Attributes inherited from jsk_topic_tools::ConnectionBasedNodelet
bool always_subscribe_
 A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~always_subscribe parameter. More...
 
std::vector< image_transport::CameraPublishercamera_publishers_
 List of watching camera publishers. More...
 
boost::mutex connection_mutex_
 mutex to call subscribe() and unsubscribe() in critical section. More...
 
ConnectionStatus connection_status_
 Status of connection. More...
 
bool ever_subscribed_
 A flag to check if the node has been ever subscribed or not. More...
 
std::vector< image_transport::Publisherimage_publishers_
 List of watching image publishers. More...
 
boost::shared_ptr< ros::NodeHandlenh_
 Shared pointer to nodehandle. More...
 
bool on_init_post_process_called_
 Never warning on not calling onInitPostProcess if true. More...
 
boost::shared_ptr< ros::NodeHandlepnh_
 Shared pointer to private nodehandle. More...
 
std::vector< ros::Publisherpublishers_
 List of watching publishers. More...
 
bool subscribed_
 A flag to check if any publisher is already subscribed or not. More...
 
ros::WallTimer timer_warn_never_subscribed_
 WallTimer instance for warning about no connection. More...
 
ros::WallTimer timer_warn_on_init_post_process_called_
 WallTimer instance for warning about no connection. More...
 
bool verbose_connection_
 true if ~verbose_connection or verbose_connection parameter is true. More...
 

Detailed Description

Nodelet class based on ConnectionBasedNodelet and publish diagnostic infromation periodicaly.

In default, diagnostic status is determined by vital_checker_ status. If vital_checker_ is not poked for seconds, which is specified by ~vital_rate param and defaults to 1.0 second, diagnostic status will be ERROR.

In order to utilize this, need to call VitalChecker::poke method in your callback function.

Definition at line 65 of file diagnostic_nodelet.h.

Member Typedef Documentation

Definition at line 68 of file diagnostic_nodelet.h.

Constructor & Destructor Documentation

jsk_topic_tools::DiagnosticNodelet::DiagnosticNodelet ( const std::string &  name)

Constructor and subclass need to call this.

Parameters
namename of subclass

Definition at line 40 of file diagnostic_nodelet.cpp.

Member Function Documentation

void jsk_topic_tools::DiagnosticNodelet::onInit ( )
protectedvirtual

Initialize method. Subclass should call this method in its onInit method.

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Reimplemented in jsk_topic_tools::VitalCheckerNodelet, and jsk_topic_tools::StringRelay.

Definition at line 46 of file diagnostic_nodelet.cpp.

void jsk_topic_tools::DiagnosticNodelet::updateDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

Method which is called periodically.

In default, it check vitality of vital_checker_ and if vital_checker_ is not poked for seconds, diagnostic status will be ERROR.

Parameters
statModofy stat to change status of diagnostic information.

Reimplemented in jsk_topic_tools::VitalCheckerNodelet.

Definition at line 65 of file diagnostic_nodelet.cpp.

Member Data Documentation

TimeredDiagnosticUpdater::Ptr jsk_topic_tools::DiagnosticNodelet::diagnostic_updater_
protected
const std::string jsk_topic_tools::DiagnosticNodelet::name_
protected

Name of subclass. It is set by constructor and used as Diagnostic method.

Definition at line 99 of file diagnostic_nodelet.h.

jsk_topic_tools::VitalChecker::Ptr jsk_topic_tools::DiagnosticNodelet::vital_checker_
protected

VitalChecker object wihch is used in default configuration.

Definition at line 111 of file diagnostic_nodelet.h.


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


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19