Public Member Functions | Public Attributes | Protected Attributes | List of all members
generic_updater::GenericUpdater< CommandType > Class Template Referenceabstract

#include <generic_updater.hpp>

Inheritance diagram for generic_updater::GenericUpdater< CommandType >:
Inheritance graph
[legend]

Public Member Functions

virtual operation_mode::device_update_state::DeviceUpdateState build_command (CommandType *command)=0
 
 GenericUpdater (std::vector< UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
 
void timer_callback (const ros::TimerEvent &event, int32u data_type)
 
virtual ~GenericUpdater ()
 

Public Attributes

std::vector< UpdateConfigimportant_update_configs_vector
 Contains all the important data types. More...
 
std::vector< UpdateConfiginitialization_configs_vector
 
operation_mode::device_update_state::DeviceUpdateState update_state
 

Protected Attributes

boost::shared_ptr< boost::mutex > mutex
 
ros::NodeHandle nh_tilde
 
std::vector< ros::Timertimers
 
std::queue< int32u, std::list< int32u > > unimportant_data_queue
 
std::vector< UpdateConfigupdate_configs_vector
 
int which_data_to_request
 iterate through the important or initialization data types. More...
 

Detailed Description

template<class CommandType>
class generic_updater::GenericUpdater< CommandType >

Definition at line 78 of file generic_updater.hpp.

Constructor & Destructor Documentation

template<class CommandType >
generic_updater::GenericUpdater< CommandType >::GenericUpdater ( std::vector< UpdateConfig update_configs_vector,
operation_mode::device_update_state::DeviceUpdateState  update_state 
)

Definition at line 36 of file generic_updater.cpp.

template<class CommandType >
virtual generic_updater::GenericUpdater< CommandType >::~GenericUpdater ( )
inlinevirtual

Definition at line 84 of file generic_updater.hpp.

Member Function Documentation

template<class CommandType >
virtual operation_mode::device_update_state::DeviceUpdateState generic_updater::GenericUpdater< CommandType >::build_command ( CommandType *  command)
pure virtual
template<class CommandType >
void generic_updater::GenericUpdater< CommandType >::timer_callback ( const ros::TimerEvent event,
int32u  data_type 
)

Definition at line 76 of file generic_updater.cpp.

Member Data Documentation

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::important_update_configs_vector

Contains all the important data types.

Definition at line 112 of file generic_updater.hpp.

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::initialization_configs_vector

Definition at line 109 of file generic_updater.hpp.

template<class CommandType >
boost::shared_ptr<boost::mutex> generic_updater::GenericUpdater< CommandType >::mutex
protected

Definition at line 127 of file generic_updater.hpp.

template<class CommandType >
ros::NodeHandle generic_updater::GenericUpdater< CommandType >::nh_tilde
protected

Definition at line 115 of file generic_updater.hpp.

template<class CommandType >
std::vector<ros::Timer> generic_updater::GenericUpdater< CommandType >::timers
protected

Definition at line 121 of file generic_updater.hpp.

template<class CommandType >
std::queue<int32u, std::list<int32u> > generic_updater::GenericUpdater< CommandType >::unimportant_data_queue
protected

Definition at line 123 of file generic_updater.hpp.

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::update_configs_vector
protected

Definition at line 125 of file generic_updater.hpp.

template<class CommandType >
operation_mode::device_update_state::DeviceUpdateState generic_updater::GenericUpdater< CommandType >::update_state

Definition at line 107 of file generic_updater.hpp.

template<class CommandType >
int generic_updater::GenericUpdater< CommandType >::which_data_to_request
protected

iterate through the important or initialization data types.

Definition at line 118 of file generic_updater.hpp.


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


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:58