00001 00029 #ifndef _MOTOR_UPDATER_HPP_ 00030 #define _MOTOR_UPDATER_HPP_ 00031 00032 #include <ros/ros.h> 00033 #include <vector> 00034 #include <list> 00035 #include <queue> 00036 #include <boost/smart_ptr.hpp> 00037 #include "sr_robot_lib/generic_updater.hpp" 00038 00039 #include <sr_external_dependencies/types_for_external.h> 00040 00041 extern "C" 00042 { 00043 #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h> 00044 } 00045 00046 namespace generic_updater 00047 { 00058 template<class CommandType> 00059 class MotorUpdater : 00060 public GenericUpdater<CommandType> 00061 { 00062 public: 00063 MotorUpdater(std::vector<UpdateConfig> update_configs_vector, 00064 operation_mode::device_update_state::DeviceUpdateState update_state); 00065 00073 operation_mode::device_update_state::DeviceUpdateState build_init_command(CommandType *command); 00074 00083 operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command); 00084 00085 private: 00086 // are we sending the command to the even or the uneven motors. 00087 int even_motors; 00088 }; 00089 } // namespace generic_updater 00090 00091 00092 /* For the emacs weenies in the crowd. 00093 Local Variables: 00094 c-basic-offset: 2 00095 End: 00096 */ 00097 00098 #endif