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   #include <sr_external_dependencies/external/0230_palm_edc_TS/0230_palm_edc_ethercat_protocol.h>
00043   #include <sr_external_dependencies/external/0320_palm_edc_muscle/0320_palm_edc_ethercat_protocol.h>
00044 }
00045 
00046 namespace operation_mode
00047 {
00048   namespace device_update_state
00049   {
00050     enum DeviceUpdateState
00051     {
00052       INITIALIZATION,
00053       OPERATION
00054     };
00055   }
00056 }
00057 
00058 namespace generic_updater
00059 {
00060   struct UpdateConfig
00061   {
00062     int32u what_to_update;
00063     double when_to_update;
00064   };
00065 
00076   template <class CommandType>
00077   class GenericUpdater
00078   {
00079   public:
00080     GenericUpdater(std::vector<UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state);
00081     ~GenericUpdater();
00082 
00091     virtual operation_mode::device_update_state::DeviceUpdateState build_command(CommandType* command)=0;
00092 
00100     void timer_callback(const ros::TimerEvent& event, int32u data_type);
00101 
00102     operation_mode::device_update_state::DeviceUpdateState update_state;
00104     std::vector<UpdateConfig> initialization_configs_vector;
00105 
00106   protected:
00107     ros::NodeHandle nh_tilde;
00108 
00110     std::vector<UpdateConfig> important_update_configs_vector;
00112     int which_data_to_request;
00113 
00115     std::vector<ros::Timer> timers;
00117     std::queue<int32u, std::list<int32u> > unimportant_data_queue;
00119     std::vector<UpdateConfig> update_configs_vector;
00120 
00121     boost::shared_ptr<boost::mutex> mutex;
00122   };
00123 }
00124 
00125 
00126 
00127 
00128 /* For the emacs weenies in the crowd.
00129 Local Variables:
00130    c-basic-offset: 2
00131 End:
00132 */
00133 
00134 #endif /* GENERIC_UPDATER_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:37:50