00001 00027 #ifndef SENSOR_UPDATER_HPP_ 00028 #define SENSOR_UPDATER_HPP_ 00029 00030 00031 00032 #include <ros/ros.h> 00033 #include <vector> 00034 #include <list> 00035 #include <queue> 00036 #include <boost/thread.hpp> 00037 #include <boost/smart_ptr.hpp> 00038 #include "sr_robot_lib/generic_updater.hpp" 00039 00040 #include <sr_external_dependencies/types_for_external.h> 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 class SensorUpdater : 00059 public GenericUpdater 00060 { 00061 public: 00062 SensorUpdater(std::vector<UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state); 00063 ~SensorUpdater(); 00064 00072 operation_mode::device_update_state::DeviceUpdateState build_init_command(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command); 00073 00083 operation_mode::device_update_state::DeviceUpdateState build_command(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command); 00084 00092 void timer_callback(const ros::TimerEvent& event, FROM_MOTOR_DATA_TYPE data_type); 00093 00103 bool reset(); 00104 }; 00105 } 00106 00107 00108 /* For the emacs weenies in the crowd. 00109 Local Variables: 00110 c-basic-offset: 2 00111 End: 00112 */ 00113 00114 #endif /* SENSOR_UPDATER_HPP_ */