Public Member Functions | Private Attributes
generic_updater::MotorUpdater Class Reference

#include <motor_updater.hpp>

Inheritance diagram for generic_updater::MotorUpdater:
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)
 MotorUpdater (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)
 ~MotorUpdater ()

Private Attributes

int even_motors
 are we sending the command to the even or the uneven motors.

Detailed Description

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 58 of file motor_updater.hpp.


Constructor & Destructor Documentation

Definition at line 35 of file motor_updater.cpp.

Definition at line 40 of file motor_updater.cpp.


Member Function Documentation

operation_mode::device_update_state::DeviceUpdateState generic_updater::MotorUpdater::build_command ( ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *  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.

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

Implements generic_updater::GenericUpdater.

Definition at line 85 of file motor_updater.cpp.

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.

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

Definition at line 44 of file motor_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.


Member Data Documentation

are we sending the command to the even or the uneven motors.

Definition at line 95 of file motor_updater.hpp.


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