#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_ |
Additional Inherited Members | |
![]() | |
static void | hupCalled (int sig) |
static void | sigCalled (int sig) |
![]() | |
static int | ctrl_c_hit_count_ = 0 |
Definition at line 116 of file driver_node.h.
typedef Driver::Config driver_base::DriverNode< Driver >::Config |
Definition at line 120 of file driver_node.h.
|
private |
Definition at line 159 of file driver_node.h.
|
inlinevirtual |
Definition at line 340 of file driver_node.h.
|
inline |
@fixme this variable is hokey.
Definition at line 399 of file driver_node.h.
|
protectedpure virtual |
|
protectedpure virtual |
|
protectedpure virtual |
|
protectedpure virtual |
|
inlineprivate |
Definition at line 329 of file driver_node.h.
|
inlineprivate |
Definition at line 307 of file driver_node.h.
|
inlineprivate |
Definition at line 256 of file driver_node.h.
|
inlineprivate |
Definition at line 302 of file driver_node.h.
|
inlineprivate |
Definition at line 223 of file driver_node.h.
|
inlineprivate |
Definition at line 242 of file driver_node.h.
|
inlineprivate |
Definition at line 165 of file driver_node.h.
|
protectedpure virtual |
|
inlineprivate |
Definition at line 271 of file driver_node.h.
|
inlineprivate |
Definition at line 334 of file driver_node.h.
|
inlineprivate |
Definition at line 319 of file driver_node.h.
|
inline |
Definition at line 342 of file driver_node.h.
|
inlineprivate |
@fixme need to put something more useful here.
Definition at line 230 of file driver_node.h.
|
inlineprivate |
Definition at line 324 of file driver_node.h.
|
protected |
Definition at line 134 of file driver_node.h.
|
protected |
Definition at line 136 of file driver_node.h.
|
protected |
Definition at line 138 of file driver_node.h.
|
private |
Definition at line 163 of file driver_node.h.
|
private |
Definition at line 156 of file driver_node.h.
|
protected |
Definition at line 131 of file driver_node.h.
|
private |
Definition at line 144 of file driver_node.h.
|
private |
Definition at line 161 of file driver_node.h.
|
protected |
Definition at line 132 of file driver_node.h.
|
protected |
Definition at line 137 of file driver_node.h.
|
private |
Definition at line 154 of file driver_node.h.
|
protected |
Definition at line 133 of file driver_node.h.