#include <sensor_updater.hpp>
Public Member Functions | |
operation_mode::device_update_state::DeviceUpdateState | build_command (CommandType *command) |
operation_mode::device_update_state::DeviceUpdateState | build_init_command (CommandType *command) |
bool | reset () |
SensorUpdater (std::vector< UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
Public Member Functions inherited from generic_updater::GenericUpdater< CommandType > | |
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 () |
Additional Inherited Members | |
Public Attributes inherited from generic_updater::GenericUpdater< CommandType > | |
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 inherited from generic_updater::GenericUpdater< CommandType > | |
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 57 of file sensor_updater.hpp.
generic_updater::SensorUpdater< CommandType >::SensorUpdater | ( | std::vector< UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 37 of file sensor_updater.cpp.
|
virtual |
Implements generic_updater::GenericUpdater< CommandType >.
Definition at line 91 of file sensor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::SensorUpdater< CommandType >::build_init_command | ( | CommandType * | command | ) |
Definition at line 44 of file sensor_updater.cpp.
bool generic_updater::SensorUpdater< CommandType >::reset | ( | ) |
Definition at line 131 of file sensor_updater.cpp.