Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
driver_base::DriverNode< Driver > Class Template Referenceabstract

#include <driver_node.h>

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

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< Configreconfigure_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 Public Member Functions inherited from driver_base::AbstractDriverNode
static void hupCalled (int sig)
 
static void sigCalled (int sig)
 
- Static Public Attributes inherited from driver_base::AbstractDriverNode
static int ctrl_c_hit_count_ = 0
 

Detailed Description

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

Definition at line 84 of file driver_node.h.

Member Typedef Documentation

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

Definition at line 88 of file driver_node.h.

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

Definition at line 127 of file driver_node.h.

Constructor & Destructor Documentation

template<class Driver >
virtual driver_base::DriverNode< Driver >::~DriverNode ( )
inlinevirtual

Definition at line 308 of file driver_node.h.

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

this variable is hokey.

Definition at line 367 of file driver_node.h.

Member Function Documentation

template<class Driver >
virtual void driver_base::DriverNode< Driver >::addDiagnostics ( )
protectedpure virtual
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addOpenedTests ( )
protectedpure virtual
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addRunningTests ( )
protectedpure virtual
template<class Driver >
virtual void driver_base::DriverNode< Driver >::addStoppedTests ( )
protectedpure virtual
template<class Driver >
void driver_base::DriverNode< Driver >::closeTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 297 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::idTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 275 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::interruptionTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate
Todo:
need to set num_subscribed_topics_ somewhere.

Definition at line 224 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::openTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 270 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::prepareDiagnostics ( )
inlineprivate

Definition at line 191 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::prepareSelfTests ( )
inlineprivate

Definition at line 210 of file driver_node.h.

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

Definition at line 133 of file driver_node.h.

template<class Driver >
virtual void driver_base::DriverNode< Driver >::reconfigureHook ( int  level)
protectedpure virtual
template<class Driver >
void driver_base::DriverNode< Driver >::reliableGoStateTest ( diagnostic_updater::DiagnosticStatusWrapper status,
drv_state_t  target_state 
)
inlineprivate

Definition at line 239 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::resumeTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 302 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::runTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 287 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 310 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::statusDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
inlineprivate

need to put something more useful here.

Definition at line 198 of file driver_node.h.

template<class Driver >
void driver_base::DriverNode< Driver >::stopTest ( diagnostic_updater::DiagnosticStatusWrapper status)
inlineprivate

Definition at line 292 of file driver_node.h.

Member Data Documentation

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

Definition at line 102 of file driver_node.h.

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

Definition at line 104 of file driver_node.h.

template<class Driver >
diagnostic_updater::CompositeDiagnosticTask driver_base::DriverNode< Driver >::driver_status_diagnostic_
protected

Definition at line 106 of file driver_node.h.

template<class Driver >
diagnostic_updater::FunctionDiagnosticTask driver_base::DriverNode< Driver >::driver_status_standard_diagnostic_
private

Definition at line 131 of file driver_node.h.

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

Definition at line 124 of file driver_node.h.

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

Definition at line 99 of file driver_node.h.

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

Definition at line 112 of file driver_node.h.

template<class Driver >
drv_state_t driver_base::DriverNode< Driver >::pre_self_test_driver_state_
private

Definition at line 129 of file driver_node.h.

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

Definition at line 100 of file driver_node.h.

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

Definition at line 105 of file driver_node.h.

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

Definition at line 122 of file driver_node.h.

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

Definition at line 101 of file driver_node.h.


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


driver_base
Author(s): Blaise Gassend
autogenerated on Tue Mar 23 2021 02:23:29