Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes
driver_base::DriverNode< Driver > Class Template Reference

#include <driver_node.h>

Inheritance diagram for driver_base::DriverNode< Driver >:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

template<class Driver>
class driver_base::DriverNode< Driver >

Definition at line 83 of file driver_node.h.


Member Typedef Documentation

template<class Driver >
typedef Driver::Config driver_base::DriverNode< Driver >::Config

Definition at line 87 of file driver_node.h.

template<class Driver >
typedef Driver::state_t driver_base::DriverNode< Driver >::drv_state_t [private]

Definition at line 126 of file driver_node.h.


Constructor & Destructor Documentation

template<class Driver >
virtual driver_base::DriverNode< Driver >::~DriverNode ( ) [inline, virtual]

Definition at line 307 of file driver_node.h.

template<class Driver >
driver_base::DriverNode< Driver >::DriverNode ( ros::NodeHandle nh) [inline]

this variable is hokey.

Definition at line 366 of file driver_node.h.


Member Function Documentation

template<class Driver >
virtual void driver_base::DriverNode< Driver >::addDiagnostics ( ) [protected, pure virtual]
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addOpenedTests ( ) [protected, pure virtual]
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addRunningTests ( ) [protected, pure virtual]
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addStoppedTests ( ) [protected, pure virtual]
template<class Driver >
void driver_base::DriverNode< Driver >::closeTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 296 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::idTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 274 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::interruptionTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]
Todo:
need to set num_subscribed_topics_ somewhere.

Definition at line 223 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::openTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 269 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::prepareDiagnostics ( ) [inline, private]

Definition at line 190 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::prepareSelfTests ( ) [inline, private]

Definition at line 209 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::reconfigure ( Config config,
uint32_t  level 
) [inline, private]
Todo:
Move this into the Driver class?

Definition at line 132 of file driver_node.h.

template<class Driver >
virtual void driver_base::DriverNode< Driver >::reconfigureHook ( int  level) [protected, pure virtual]
template<class Driver >
void driver_base::DriverNode< Driver >::reliableGoStateTest ( diagnostic_updater::DiagnosticStatusWrapper status,
drv_state_t  target_state 
) [inline, private]

Definition at line 238 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::resumeTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 301 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::runTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 286 of file driver_node.h.

template<class Driver >
int driver_base::DriverNode< Driver >::spin ( ) [inline]
Todo:
What happens if thread creation fails?
Todo:
Do something about exit status?
Todo:
Work on return type here.

Definition at line 309 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::statusDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat) [inline, private]

need to put something more useful here.

Definition at line 197 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::stopTest ( diagnostic_updater::DiagnosticStatusWrapper status) [inline, private]

Definition at line 291 of file driver_node.h.


Member Data Documentation

template<class Driver >
diagnostic_updater::Updater driver_base::DriverNode< Driver >::diagnostic_ [protected]

Definition at line 101 of file driver_node.h.

template<class Driver >
Driver driver_base::DriverNode< Driver >::driver_ [protected]

Definition at line 103 of file driver_node.h.

Definition at line 105 of file driver_node.h.

Definition at line 130 of file driver_node.h.

template<class Driver >
int driver_base::DriverNode< Driver >::exit_status_ [private]

Definition at line 123 of file driver_node.h.

template<class Driver >
ros::NodeHandle driver_base::DriverNode< Driver >::node_handle_ [protected]

Definition at line 98 of file driver_node.h.

template<class Driver >
int driver_base::DriverNode< Driver >::num_subscribed_topics_ [private]

Definition at line 111 of file driver_node.h.

Definition at line 128 of file driver_node.h.

template<class Driver >
ros::NodeHandle driver_base::DriverNode< Driver >::private_node_handle_ [protected]

Definition at line 99 of file driver_node.h.

template<class Driver >
dynamic_reconfigure::Server<Config> driver_base::DriverNode< Driver >::reconfigure_server_ [protected]

Definition at line 104 of file driver_node.h.

template<class Driver >
boost::shared_ptr<boost::thread> driver_base::DriverNode< Driver >::ros_thread_ [private]

Definition at line 121 of file driver_node.h.

template<class Driver >
self_test::TestRunner driver_base::DriverNode< Driver >::self_test_ [protected]

Definition at line 100 of file driver_node.h.


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


driver_base
Author(s): Blaise Gassend
autogenerated on Fri Jan 3 2014 11:19:50