#include <motor_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) |
MotorUpdater (std::vector< UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state) | |
Private Attributes | |
int | even_motors |
The Motor 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/motor_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 motor_updater.hpp.
generic_updater::MotorUpdater< CommandType >::MotorUpdater | ( | std::vector< UpdateConfig > | update_configs_vector, |
operation_mode::device_update_state::DeviceUpdateState | update_state | ||
) |
Definition at line 37 of file motor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::MotorUpdater< CommandType >::build_command | ( | CommandType * | command | ) | [virtual] |
Building the motor command. This function is called at each packCommand() call. 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 motor. |
Implements generic_updater::GenericUpdater< CommandType >.
Definition at line 99 of file motor_updater.cpp.
operation_mode::device_update_state::DeviceUpdateState generic_updater::MotorUpdater< CommandType >::build_init_command | ( | CommandType * | command | ) |
Building the motor initialization command. This function is called at each packCommand() call. It builds initialization commands if the update state is operation_mode::device_update_state::INITIALIZATION.
command | The command which will be sent to the motor. |
Definition at line 44 of file motor_updater.cpp.
int generic_updater::MotorUpdater< CommandType >::even_motors [private] |
Definition at line 87 of file motor_updater.hpp.