Public Member Functions | Public Attributes | Protected Attributes
generic_updater::GenericUpdater< CommandType > Class Template Reference

#include <generic_updater.hpp>

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

List of all members.

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

Public Attributes

std::vector< UpdateConfiginitialization_configs_vector
 Contains all the initialization data types.
operation_mode::device_update_state::DeviceUpdateState update_state

Protected Attributes

std::vector< UpdateConfigimportant_update_configs_vector
 Contains all the important data types.
boost::shared_ptr< boost::mutexmutex
ros::NodeHandle nh_tilde
std::vector< ros::Timertimers
 All the timers for the unimportant data types.
std::queue< int32u, std::list
< int32u > > 
unimportant_data_queue
 A queue containing the unimportant data types we want to ask for next time (empty most of the time).
std::vector< UpdateConfigupdate_configs_vector
 Contains the vector with the update configs for every command. We store it to be able to reinitialize.
int which_data_to_request
 iterate through the important or initialization data types.

Detailed Description

template<class CommandType>
class generic_updater::GenericUpdater< CommandType >

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 77 of file generic_updater.hpp.


Constructor & Destructor Documentation

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

Definition at line 36 of file generic_updater.cpp.

template<class CommandType >
generic_updater::GenericUpdater< CommandType >::~GenericUpdater ( )

Definition at line 74 of file generic_updater.cpp.


Member Function Documentation

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

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

Implemented in generic_updater::SensorUpdater< CommandType >, generic_updater::MotorUpdater< CommandType >, and generic_updater::MuscleUpdater< CommandType >.

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

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

Definition at line 79 of file generic_updater.cpp.


Member Data Documentation

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::important_update_configs_vector [protected]

Contains all the important data types.

Definition at line 110 of file generic_updater.hpp.

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::initialization_configs_vector

Contains all the initialization data types.

Definition at line 104 of file generic_updater.hpp.

template<class CommandType >
boost::shared_ptr<boost::mutex> generic_updater::GenericUpdater< CommandType >::mutex [protected]

Definition at line 121 of file generic_updater.hpp.

template<class CommandType >
ros::NodeHandle generic_updater::GenericUpdater< CommandType >::nh_tilde [protected]

Definition at line 107 of file generic_updater.hpp.

template<class CommandType >
std::vector<ros::Timer> generic_updater::GenericUpdater< CommandType >::timers [protected]

All the timers for the unimportant data types.

Definition at line 115 of file generic_updater.hpp.

template<class CommandType >
std::queue<int32u, std::list<int32u> > generic_updater::GenericUpdater< CommandType >::unimportant_data_queue [protected]

A queue containing the unimportant data types we want to ask for next time (empty most of the time).

Definition at line 117 of file generic_updater.hpp.

template<class CommandType >
std::vector<UpdateConfig> generic_updater::GenericUpdater< CommandType >::update_configs_vector [protected]

Contains the vector with the update configs for every command. We store it to be able to reinitialize.

Definition at line 119 of file generic_updater.hpp.

Definition at line 102 of file generic_updater.hpp.

template<class CommandType >
int generic_updater::GenericUpdater< CommandType >::which_data_to_request [protected]

iterate through the important or initialization data types.

Definition at line 112 of file generic_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 Mon Oct 6 2014 07:37:50