#include <generic_updater.hpp>
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< UpdateConfig > | important_update_configs_vector |
Contains all the important data types. More... | |
std::vector< UpdateConfig > | initialization_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::Timer > | timers |
std::queue< int32u, std::list< int32u > > | unimportant_data_queue |
std::vector< UpdateConfig > | update_configs_vector |
int | which_data_to_request |
iterate through the important or initialization data types. More... | |
Definition at line 78 of file generic_updater.hpp.
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.
|
inlinevirtual |
Definition at line 84 of file generic_updater.hpp.
|
pure virtual |
void generic_updater::GenericUpdater< CommandType >::timer_callback | ( | const ros::TimerEvent & | event, |
int32u | data_type | ||
) |
Definition at line 76 of file generic_updater.cpp.
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.
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::initialization_configs_vector |
Definition at line 109 of file generic_updater.hpp.
|
protected |
Definition at line 127 of file generic_updater.hpp.
|
protected |
Definition at line 115 of file generic_updater.hpp.
|
protected |
Definition at line 121 of file generic_updater.hpp.
|
protected |
Definition at line 123 of file generic_updater.hpp.
|
protected |
Definition at line 125 of file generic_updater.hpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::GenericUpdater< CommandType >::update_state |
Definition at line 107 of file generic_updater.hpp.
|
protected |
iterate through the important or initialization data types.
Definition at line 118 of file generic_updater.hpp.