Class to facilitate the creation of component self-tests. More...
#include <self_test.h>
Public Member Functions | |
void | checkTest () |
Check if a self-test is pending. If so, start it and wait for it to complete. More... | |
void | setID (std::string id) |
Sets the ID of the part being tested. More... | |
TestRunner (ros::NodeHandle h=ros::NodeHandle(), ros::NodeHandle ph=ros::NodeHandle("~")) | |
Constructs a dispatcher. More... | |
Public Member Functions inherited from diagnostic_updater::DiagnosticTaskVector | |
void | add (const std::string &name, TaskFunction f) |
void | add (DiagnosticTask &task) |
void | add (const std::string name, T *c, void(T::*f)(diagnostic_updater::DiagnosticStatusWrapper &)) |
bool | removeByName (const std::string name) |
Private Member Functions | |
bool | doTest (diagnostic_msgs::SelfTest::Request &req, diagnostic_msgs::SelfTest::Response &res) |
Private Attributes | |
std::string | id_ |
ros::NodeHandle | node_handle_ |
ros::NodeHandle | private_node_handle_ |
ros::CallbackQueue | self_test_queue_ |
ros::ServiceServer | service_server_ |
bool | verbose |
Additional Inherited Members | |
Protected Member Functions inherited from diagnostic_updater::DiagnosticTaskVector | |
void | addInternal (DiagnosticTaskInternal &task) |
const std::vector< DiagnosticTaskInternal > & | getTasks () |
Protected Attributes inherited from diagnostic_updater::DiagnosticTaskVector | |
boost::mutex | lock_ |
Class to facilitate the creation of component self-tests.
The self_test::TestRunner class advertises the "self_test" service, and maintains a list of pretests and tests. When "self_test" is invoked, TestRunner waits for a suitable time to interrupt the node and run the tests. Results from the tests are collected and returned to the caller.
self_test::TestRunner's is a derived class from diagnostic_updater::DiagnosticTaskVector. For documentation of the add() methods you will have to refer to the base class's documentation.
Definition at line 68 of file self_test.h.
|
inline |
Constructs a dispatcher.
owner | Class that owns this dispatcher. This is used as the default class for tests that are member-functions. |
h | NodeHandle from which to work. (Currently unused?) |
Definition at line 90 of file self_test.h.
|
inline |
Check if a self-test is pending. If so, start it and wait for it to complete.
Definition at line 107 of file self_test.h.
|
inlineprivate |
The service callback for the "self-test" service.
Definition at line 130 of file self_test.h.
|
inline |
Sets the ID of the part being tested.
This method is expected to be called by one of the tests during the self-test.
id | : String that identifies the piece of hardware being tested. |
Definition at line 121 of file self_test.h.
|
private |
Definition at line 75 of file self_test.h.
|
private |
Definition at line 73 of file self_test.h.
|
private |
Definition at line 74 of file self_test.h.
|
private |
Definition at line 72 of file self_test.h.
|
private |
Definition at line 71 of file self_test.h.
|
private |
Definition at line 77 of file self_test.h.