Public Member Functions
generic_updater::SensorUpdater Class Reference

#include <sensor_updater.hpp>

Inheritance diagram for generic_updater::SensorUpdater:
Inheritance graph
[legend]

List of all members.

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 ()

Detailed Description

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.


Constructor & Destructor Documentation

Definition at line 34 of file sensor_updater.cpp.

Definition at line 39 of file sensor_updater.cpp.


Member Function Documentation

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.

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

Implements generic_updater::GenericUpdater.

Definition at line 81 of file sensor_updater.cpp.

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 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.

Returns:
true if RESET added to the top queue.

Definition at line 114 of file sensor_updater.cpp.

A timer callback for the unimportant data. The frequency of this callback is defined in the config file.

Parameters:
event
data_typeThe unimportant data type we want to ask for.

Reimplemented from generic_updater::GenericUpdater.


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


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:02:17