#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) | |
~SensorUpdater () |
The Sensor Updater builds the next command we want to send to the hand. We can ask for different types of data at different rates. The data and their rates are defined in the sr_ethercat_hand_config/rates/sensor_data_polling.yaml The important data are refreshed as often as possible (they have a -1. refresh rate in the config file).
The unimportant data are refreshed at their given rate (the value is defined in the config in seconds).
Definition at line 59 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 35 of file sensor_updater.cpp.
generic_updater::SensorUpdater< CommandType >::~SensorUpdater | ( | ) |
Definition at line 41 of file sensor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::SensorUpdater< CommandType >::build_command | ( | CommandType * | command | ) | [virtual] |
Updates the command to send to the hand. This function is called at each packCommand() call. Ask for the relevant information for the tactiles. If an unimportant data is waiting then we send it, otherwise, we send the next important data.
command | The command which will be sent to the palm. |
Implements generic_updater::GenericUpdater< CommandType >.
Definition at line 85 of file sensor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::SensorUpdater< CommandType >::build_init_command | ( | CommandType * | command | ) |
Updates the initialization command to send to the hand. This function is called at each packCommand() call. Ask for the relevant information for the tactiles.
command | The command which will be sent to the palm. |
Definition at line 46 of file sensor_updater.cpp.
bool generic_updater::SensorUpdater< CommandType >::reset | ( | ) |
Will send the reset command to the tactiles, on next build command call.
Simply adds the reset command to the unimportant_data_queue.
Definition at line 119 of file sensor_updater.cpp.