$search

NodeStatePublisher Class Reference

#include <state_publisher.h>

List of all members.

Public Member Functions

void heartbeat_timer_cb (const ros::WallTimerEvent &event)
 NodeStatePublisher (const char *package_name, const char *node_type, ros::NodeHandle &nh)
void send_warning (std::string machine_msg, std::string human_msg)
void set_error (std::string machine_msg, std::string msg)
void set_fatal (std::string machine_msg, std::string human_msg)
void set_recovering (std::string machine_msg, std::string msg)
void set_running ()
void vsend_warning (const char *machine_msg, const char *human_format,...)
void vset_error (const char *machine_msg, const char *human_format,...)
void vset_fatal (const char *machine_msg, const char *human_format,...)
void vset_recovering (const char *machine_msg, const char *human_format,...)
 ~NodeStatePublisher ()

Private Member Functions

void publish_state ()

Private Attributes

ros::WallTimer __heartbeat_timer
ros::NodeHandle__nh
nodemon_msgs::NodeState __state_msg
ros::Publisher __state_pub

Detailed Description

Node state publisher. This class provides an interface to send heartbeat messages and specific error information.

To use this class, simply instantiate the class in your code with the node handle. As soon as set_running() is called, the state publisher starts to send periodical heartbeat messages. To switch the state, call any of set_fatal(), set_error(), or set_recovering() for the respective state. Call set_running() again to return to the normal operation state. Only in this state the timestamp of the message is updated automatically. If you want to indicate aliveness, for example during recovering, call the respective set methods by yourself.

Author:
Tim Niemueller

Definition at line 31 of file state_publisher.h.


Constructor & Destructor Documentation

NodeStatePublisher::NodeStatePublisher ( const char *  package_name,
const char *  node_type,
ros::NodeHandle nh 
)

Constructor.

Parameters:
package_name the name of the package that contains the node
node_type the node type, this is the name of the executable, only the base name is used.
nh node handle to register with

Definition at line 54 of file state_publisher.cpp.

NodeStatePublisher::~NodeStatePublisher (  ) 

Destructor.

Definition at line 82 of file state_publisher.cpp.


Member Function Documentation

void NodeStatePublisher::heartbeat_timer_cb ( const ros::WallTimerEvent event  ) 

Callback for the heartbeat timer event.

Parameters:
event event description

Definition at line 316 of file state_publisher.cpp.

void NodeStatePublisher::publish_state (  )  [inline, private]

Publish the current state message.

Definition at line 94 of file state_publisher.cpp.

void NodeStatePublisher::send_warning ( std::string  machine_msg,
std::string  human_msg 
)

Send warning message. Warning messages are meant to indicate a serious problem to the developer or user, that the node was able to work around or solve this time, but that might also cause trouble. The warning message is modeled as a transitional state, i.e. an automatic transition is made back to the previous state after the warning has been processed.

Parameters:
machine_msg a warning message describing the problem briefly in a machine parseable format
human_msg a warning message describing the problem briefly in a human readable format

Definition at line 194 of file state_publisher.cpp.

void NodeStatePublisher::set_error ( std::string  machine_msg,
std::string  human_msg 
)

Set the non-fatal error state. The error state is meant for errors from which the node can recover at run-time. The node may require input from other nodes to start recovering, or it can start recovery by itself if possible and without risk of damaging the robot or harming humans. Once recovery is started, call set_recovering(). The message should give a meaningful and concise description of the cause of the error.

Parameters:
machine_msg message describing the cause of the error in a machine parseable format
machine_msg message describing the cause of the error in a human readable format

Definition at line 149 of file state_publisher.cpp.

void NodeStatePublisher::set_fatal ( std::string  machine_msg,
std::string  human_msg 
)

Set the fatal state. The fatal state is meant for errors from which the node cannot recover without completely restarting it. The message should give a meaningful and concise description of the cause of the error.

Parameters:
machine_msg message describing the cause of the fatal error in a machine parseable format
machine_msg message describing the cause of the fatal error in a human readable format

Definition at line 125 of file state_publisher.cpp.

void NodeStatePublisher::set_recovering ( std::string  machine_msg,
std::string  human_msg 
)

Set recovering state. The recovery state is meant to describe that the node is in the process of returning to an operational state. During that time it cannot process any new requests or commands. Once recovery is finished call set_running() to indicate that the node is fully operational again.

Parameters:
machine_msg a message describing the recovery method or procedure briefly in a machine parseable format, e.g. "move_arm_safe_pos".
human_msg a message describing the recovery method or procedure briefly in a human readable format, e.g. "moving arm to safe position".

Definition at line 171 of file state_publisher.cpp.

void NodeStatePublisher::set_running (  ) 

Set the running state. The state publisher will start to send periodical heartbeat messages with updated time stamps.

Definition at line 105 of file state_publisher.cpp.

void NodeStatePublisher::vsend_warning ( const char *  machine_msg,
const char *  human_format,
  ... 
)

Send warning message. This is a convenience method with the same effects as send_warning().

Parameters:
machine_msg machine parseable message
human_format Format of the human readable string

Definition at line 288 of file state_publisher.cpp.

void NodeStatePublisher::vset_error ( const char *  machine_msg,
const char *  human_format,
  ... 
)

Set the error state from formatted string. This is a convenience method with the same effects as set_error().

Parameters:
machine_msg machine parseable message
human_format Format of the human readable string

Definition at line 238 of file state_publisher.cpp.

void NodeStatePublisher::vset_fatal ( const char *  machine_msg,
const char *  human_format,
  ... 
)

Set the fatal state from formatted string. This is a convenience method with the same effects as set_fatal().

Parameters:
machine_msg machine parseable message
human_format Format of the human readable string

Definition at line 213 of file state_publisher.cpp.

void NodeStatePublisher::vset_recovering ( const char *  machine_msg,
const char *  human_format,
  ... 
)

Set the recovering state from formatted string. This is a convenience method with the same effects as set_recovering().

Parameters:
machine_msg machine parseable message
human_format Format of the human readable string

Definition at line 263 of file state_publisher.cpp.


Member Data Documentation

Definition at line 59 of file state_publisher.h.

Definition at line 57 of file state_publisher.h.

Definition at line 62 of file state_publisher.h.

Definition at line 61 of file state_publisher.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


nodemon_cpp
Author(s): Tim Niemueller
autogenerated on Tue Mar 5 12:26:53 2013