generic_updater.hpp
Go to the documentation of this file.
00001 
00029 #ifndef GENERIC_UPDATER_HPP_
00030 #define GENERIC_UPDATER_HPP_
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_external_dependencies/types_for_external.h>
00039 extern "C"
00040 {
00041   #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h>
00042 }
00043 
00044 namespace operation_mode
00045 {
00046   namespace device_update_state
00047   {
00048     enum DeviceUpdateState
00049     {
00050       INITIALIZATION,
00051       OPERATION
00052     };
00053   }
00054 }
00055 
00056 namespace generic_updater
00057 {
00058   struct UpdateConfig
00059   {
00060     int32u what_to_update;
00061     double when_to_update;
00062   };
00063 
00074   class GenericUpdater
00075   {
00076   public:
00077     GenericUpdater(std::vector<UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state);
00078     ~GenericUpdater();
00079 
00088     virtual operation_mode::device_update_state::DeviceUpdateState build_command(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND* command)=0;
00089 
00097     void timer_callback(const ros::TimerEvent& event, FROM_MOTOR_DATA_TYPE data_type);
00098 
00099     operation_mode::device_update_state::DeviceUpdateState update_state;
00101     std::vector<UpdateConfig> initialization_configs_vector;
00102 
00103   protected:
00104     ros::NodeHandle nh_tilde;
00105 
00107     std::vector<UpdateConfig> important_update_configs_vector;
00109     int which_data_to_request;
00110 
00112     std::vector<ros::Timer> timers;
00114     std::queue<int32u, std::list<int32u> > unimportant_data_queue;
00116     std::vector<UpdateConfig> update_configs_vector;
00117 
00118     boost::shared_ptr<boost::mutex> mutex;
00119   };
00120 }
00121 
00122 
00123 
00124 
00125 /* For the emacs weenies in the crowd.
00126 Local Variables:
00127    c-basic-offset: 2
00128 End:
00129 */
00130 
00131 #endif /* GENERIC_UPDATER_HPP_ */


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