Public Member Functions
generic_updater::SensorUpdater< CommandType > Class Template Reference

#include <sensor_updater.hpp>

Inheritance diagram for generic_updater::SensorUpdater< CommandType >:
Inheritance graph
[legend]

List of all members.

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)

Detailed Description

template<class CommandType>
class generic_updater::SensorUpdater< CommandType >

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 57 of file sensor_updater.hpp.


Constructor & Destructor Documentation

template<class CommandType >
generic_updater::SensorUpdater< CommandType >::SensorUpdater ( std::vector< UpdateConfig update_configs_vector,
operation_mode::device_update_state::DeviceUpdateState  update_state 
)

Definition at line 38 of file sensor_updater.cpp.


Member Function Documentation

template<class CommandType >
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.

Parameters:
commandThe command which will be sent to the palm.
Returns:
current update state

Implements generic_updater::GenericUpdater< CommandType >.

Definition at line 92 of file sensor_updater.cpp.

template<class CommandType >
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.

Parameters:
commandThe command which will be sent to the palm.
Returns:
current update state

Definition at line 45 of file sensor_updater.cpp.

template<class CommandType >
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.

Returns:
true if RESET added to the top queue.

Definition at line 132 of file sensor_updater.cpp.


The documentation for this class was generated from the following files:


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:26