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/mutex.hpp>
00037 #include <boost/smart_ptr.hpp>
00038 #include <sr_external_dependencies/types_for_external.h>
00039 
00040 extern "C"
00041 {
00042 #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h>
00043 #include <sr_external_dependencies/external/0230_palm_edc_TS/0230_palm_edc_ethercat_protocol.h>
00044 #include <sr_external_dependencies/external/0320_palm_edc_muscle/0320_palm_edc_ethercat_protocol.h>
00045 }
00046 
00047 namespace operation_mode
00048 {
00049 namespace device_update_state
00050 {
00051   enum DeviceUpdateState
00052   {
00053     INITIALIZATION,
00054     OPERATION
00055   };
00056 }   // namespace device_update_state
00057 }  // namespace operation_mode
00058 
00059 namespace generic_updater
00060 {
00061 struct UpdateConfig
00062 {
00063   int32u what_to_update;
00064   double when_to_update;
00065 };
00066 
00077 template<class CommandType>
00078 class GenericUpdater
00079 {
00080 public:
00081   GenericUpdater(std::vector<UpdateConfig> update_configs_vector,
00082                  operation_mode::device_update_state::DeviceUpdateState update_state);
00083 
00084   virtual ~GenericUpdater()
00085   {
00086   }
00087 
00096   virtual operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command) = 0;
00097 
00105   void timer_callback(const ros::TimerEvent &event, int32u data_type);
00106 
00107   operation_mode::device_update_state::DeviceUpdateState update_state;
00108   // Contains all the initialization data types.
00109   std::vector<UpdateConfig> initialization_configs_vector;
00110 
00112   std::vector<UpdateConfig> important_update_configs_vector;
00113 
00114 protected:
00115   ros::NodeHandle nh_tilde;
00116 
00118   int which_data_to_request;
00119 
00120   // All the timers for the unimportant data types.
00121   std::vector<ros::Timer> timers;
00122   // A queue containing the unimportant data types we want to ask for next time (empty most of the time).
00123   std::queue<int32u, std::list<int32u> > unimportant_data_queue;
00124   // Contains the vector with the update configs for every command. We store it to be able to reinitialize.
00125   std::vector<UpdateConfig> update_configs_vector;
00126 
00127   boost::shared_ptr<boost::mutex> mutex;
00128 };
00129 }  // namespace generic_updater
00130 
00131 
00132 /* For the emacs weenies in the crowd.
00133 Local Variables:
00134    c-basic-offset: 2
00135 End:
00136 */
00137 
00138 #endif /* GENERIC_UPDATER_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:26