#include <sensor_updater.hpp>
Public Member Functions | |
operation_mode::device_update_state::DeviceUpdateState | build_command (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *command) |
operation_mode::device_update_state::DeviceUpdateState | build_init_command (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *command) |
bool | reset () |
SensorUpdater (std::vector< UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
void | timer_callback (const ros::TimerEvent &event, FROM_MOTOR_DATA_TYPE data_type) |
~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 58 of file sensor_updater.hpp.
generic_updater::SensorUpdater::SensorUpdater | ( | std::vector< UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 34 of file sensor_updater.cpp.
Definition at line 39 of file sensor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::SensorUpdater::build_command | ( | ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND * | 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.
Definition at line 81 of file sensor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::SensorUpdater::build_init_command | ( | ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND * | 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 43 of file sensor_updater.cpp.
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 114 of file sensor_updater.cpp.
void generic_updater::SensorUpdater::timer_callback | ( | const ros::TimerEvent & | event, |
FROM_MOTOR_DATA_TYPE | data_type | ||
) |
A timer callback for the unimportant data. The frequency of this callback is defined in the config file.
event | |
data_type | The unimportant data type we want to ask for. |
Reimplemented from generic_updater::GenericUpdater.