#include <driver_node.h>

Public Types | |
| typedef Driver::Config | Config |
Public Member Functions | |
| DriverNode (ros::NodeHandle &nh) | |
| int | spin () |
| virtual | ~DriverNode () |
Protected Member Functions | |
| virtual void | addDiagnostics ()=0 |
| virtual void | addOpenedTests ()=0 |
| virtual void | addRunningTests ()=0 |
| virtual void | addStoppedTests ()=0 |
| virtual void | reconfigureHook (int level)=0 |
Protected Attributes | |
| diagnostic_updater::Updater | diagnostic_ |
| Driver | driver_ |
| diagnostic_updater::CompositeDiagnosticTask | driver_status_diagnostic_ |
| ros::NodeHandle | node_handle_ |
| ros::NodeHandle | private_node_handle_ |
| dynamic_reconfigure::Server < Config > | reconfigure_server_ |
| self_test::TestRunner | self_test_ |
Private Types | |
| typedef Driver::state_t | drv_state_t |
Private Member Functions | |
| void | closeTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | idTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | interruptionTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | openTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | prepareDiagnostics () |
| void | prepareSelfTests () |
| void | reconfigure (Config &config, uint32_t level) |
| void | reliableGoStateTest (diagnostic_updater::DiagnosticStatusWrapper &status, drv_state_t target_state) |
| void | resumeTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | runTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
| void | statusDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
| void | stopTest (diagnostic_updater::DiagnosticStatusWrapper &status) |
Private Attributes | |
| diagnostic_updater::FunctionDiagnosticTask | driver_status_standard_diagnostic_ |
| int | exit_status_ |
| int | num_subscribed_topics_ |
| drv_state_t | pre_self_test_driver_state_ |
| boost::shared_ptr< boost::thread > | ros_thread_ |
Definition at line 81 of file driver_node.h.
| typedef Driver::Config driver_base::DriverNode< Driver >::Config |
Definition at line 85 of file driver_node.h.
typedef Driver::state_t driver_base::DriverNode< Driver >::drv_state_t [private] |
Definition at line 124 of file driver_node.h.
| virtual driver_base::DriverNode< Driver >::~DriverNode | ( | ) | [inline, virtual] |
Definition at line 305 of file driver_node.h.
| driver_base::DriverNode< Driver >::DriverNode | ( | ros::NodeHandle & | nh | ) | [inline] |
this variable is hokey.
Definition at line 364 of file driver_node.h.
| virtual void driver_base::DriverNode< Driver >::addDiagnostics | ( | ) | [protected, pure virtual] |
| virtual void driver_base::DriverNode< Driver >::addOpenedTests | ( | ) | [protected, pure virtual] |
| virtual void driver_base::DriverNode< Driver >::addRunningTests | ( | ) | [protected, pure virtual] |
| virtual void driver_base::DriverNode< Driver >::addStoppedTests | ( | ) | [protected, pure virtual] |
| void driver_base::DriverNode< Driver >::closeTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 294 of file driver_node.h.
| void driver_base::DriverNode< Driver >::idTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 272 of file driver_node.h.
| void driver_base::DriverNode< Driver >::interruptionTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 221 of file driver_node.h.
| void driver_base::DriverNode< Driver >::openTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 267 of file driver_node.h.
| void driver_base::DriverNode< Driver >::prepareDiagnostics | ( | ) | [inline, private] |
Definition at line 188 of file driver_node.h.
| void driver_base::DriverNode< Driver >::prepareSelfTests | ( | ) | [inline, private] |
Definition at line 207 of file driver_node.h.
| void driver_base::DriverNode< Driver >::reconfigure | ( | Config & | config, | |
| uint32_t | level | |||
| ) | [inline, private] |
Definition at line 130 of file driver_node.h.
| virtual void driver_base::DriverNode< Driver >::reconfigureHook | ( | int | level | ) | [protected, pure virtual] |
| void driver_base::DriverNode< Driver >::reliableGoStateTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status, | |
| drv_state_t | target_state | |||
| ) | [inline, private] |
Definition at line 236 of file driver_node.h.
| void driver_base::DriverNode< Driver >::resumeTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 299 of file driver_node.h.
| void driver_base::DriverNode< Driver >::runTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 284 of file driver_node.h.
| int driver_base::DriverNode< Driver >::spin | ( | ) | [inline] |
Definition at line 307 of file driver_node.h.
| void driver_base::DriverNode< Driver >::statusDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, private] |
need to put something more useful here.
Definition at line 195 of file driver_node.h.
| void driver_base::DriverNode< Driver >::stopTest | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) | [inline, private] |
Definition at line 289 of file driver_node.h.
diagnostic_updater::Updater driver_base::DriverNode< Driver >::diagnostic_ [protected] |
Definition at line 99 of file driver_node.h.
Driver driver_base::DriverNode< Driver >::driver_ [protected] |
Definition at line 101 of file driver_node.h.
diagnostic_updater::CompositeDiagnosticTask driver_base::DriverNode< Driver >::driver_status_diagnostic_ [protected] |
Definition at line 103 of file driver_node.h.
diagnostic_updater::FunctionDiagnosticTask driver_base::DriverNode< Driver >::driver_status_standard_diagnostic_ [private] |
Definition at line 128 of file driver_node.h.
int driver_base::DriverNode< Driver >::exit_status_ [private] |
Definition at line 121 of file driver_node.h.
ros::NodeHandle driver_base::DriverNode< Driver >::node_handle_ [protected] |
Definition at line 96 of file driver_node.h.
int driver_base::DriverNode< Driver >::num_subscribed_topics_ [private] |
Definition at line 109 of file driver_node.h.
drv_state_t driver_base::DriverNode< Driver >::pre_self_test_driver_state_ [private] |
Definition at line 126 of file driver_node.h.
ros::NodeHandle driver_base::DriverNode< Driver >::private_node_handle_ [protected] |
Definition at line 97 of file driver_node.h.
dynamic_reconfigure::Server<Config> driver_base::DriverNode< Driver >::reconfigure_server_ [protected] |
Definition at line 102 of file driver_node.h.
boost::shared_ptr<boost::thread> driver_base::DriverNode< Driver >::ros_thread_ [private] |
Definition at line 119 of file driver_node.h.
self_test::TestRunner driver_base::DriverNode< Driver >::self_test_ [protected] |
Definition at line 98 of file driver_node.h.