#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. | |
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. |
The Generic 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/xxxxx.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 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 37 of file generic_updater.cpp.
virtual generic_updater::GenericUpdater< CommandType >::~GenericUpdater | ( | ) | [inline, virtual] |
Definition at line 84 of file generic_updater.hpp.
virtual operation_mode::device_update_state::DeviceUpdateState generic_updater::GenericUpdater< CommandType >::build_command | ( | CommandType * | command | ) | [pure 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. |
Implemented in generic_updater::MotorUpdater< CommandType >, generic_updater::MuscleUpdater< CommandType >, and generic_updater::SensorUpdater< CommandType >.
void generic_updater::GenericUpdater< CommandType >::timer_callback | ( | const ros::TimerEvent & | event, |
int32u | 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. |
Definition at line 77 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.
boost::shared_ptr<boost::mutex> generic_updater::GenericUpdater< CommandType >::mutex [protected] |
Definition at line 127 of file generic_updater.hpp.
ros::NodeHandle generic_updater::GenericUpdater< CommandType >::nh_tilde [protected] |
Definition at line 115 of file generic_updater.hpp.
std::vector<ros::Timer> generic_updater::GenericUpdater< CommandType >::timers [protected] |
Definition at line 121 of file generic_updater.hpp.
std::queue<int32u, std::list<int32u> > generic_updater::GenericUpdater< CommandType >::unimportant_data_queue [protected] |
Definition at line 123 of file generic_updater.hpp.
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::update_configs_vector [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.
int generic_updater::GenericUpdater< CommandType >::which_data_to_request [protected] |
iterate through the important or initialization data types.
Definition at line 118 of file generic_updater.hpp.