motor_data_checker.hpp
Go to the documentation of this file.
00001 
00027 #ifndef MOTOR_DATA_CHECKER_HPP_
00028 #define MOTOR_DATA_CHECKER_HPP_
00029 
00030 #include <ros/ros.h>
00031 #include <vector>
00032 #include <boost/array.hpp>
00033 #include <boost/smart_ptr.hpp>
00034 #include <boost/ptr_container/ptr_vector.hpp>
00035 #include "sr_robot_lib/sr_joint_motor.hpp"
00036 #include "sr_robot_lib/generic_updater.hpp"
00037 
00038 extern "C"
00039 {
00040 #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h>
00041 }
00042 
00043 namespace generic_updater
00044 {
00045 class MessageFromMotorChecker
00046 {
00047 public:
00048   explicit MessageFromMotorChecker(int id)
00049           : motor_id_(id), received_(false)
00050   {
00051   }
00052 
00053   virtual ~MessageFromMotorChecker()
00054   {
00055   }
00056 
00057   int motor_id_;
00058 
00059   virtual void set_received();
00060 
00061   bool get_received();
00062 
00063 protected:
00064   bool received_;
00065 };
00066 
00067 class SlowMessageFromMotorChecker :
00068         public MessageFromMotorChecker
00069 {
00070 public:
00071   explicit SlowMessageFromMotorChecker(int id);
00072 
00073   boost::array<bool, MOTOR_SLOW_DATA_LAST + 1> slow_data_received;
00074 
00075   virtual void set_received(FROM_MOTOR_SLOW_DATA_TYPE slow_data_type);
00076 };
00077 
00078 class MessageChecker
00079 {
00080 public:
00081   explicit MessageChecker(FROM_MOTOR_DATA_TYPE msg_type)
00082           : msg_type(msg_type)
00083   {
00084   }
00085 
00086   FROM_MOTOR_DATA_TYPE msg_type;
00087   std::vector<MessageFromMotorChecker *> msg_from_motor_checkers;
00088 
00089   int find(int motor_id);
00090 };
00091 
00096 class MotorDataChecker
00097 {
00098 public:
00099   MotorDataChecker(std::vector<shadow_joints::Joint> joints_vector,
00100                    std::vector<UpdateConfig> initialization_configs_vector);
00101 
00102   ~MotorDataChecker();
00103 
00115   bool check_message(std::vector<shadow_joints::Joint>::iterator joint_tmp,
00116                      FROM_MOTOR_DATA_TYPE motor_data_type, int16u motor_slow_data_type);
00117 
00125   void init(std::vector<shadow_joints::Joint> joints_vector,
00126             std::vector<UpdateConfig> initialization_configs_vector);
00127 
00128 protected:
00129   static const double timeout;
00130   ros::NodeHandle nh_tilde;
00131   ros::Timer check_timeout_timer;
00132   operation_mode::device_update_state::DeviceUpdateState update_state;
00133   ros::Duration init_max_duration;
00134 
00135   void timer_callback(const ros::TimerEvent &event);
00136 
00137   bool is_everything_checked();
00138 
00139   int find(FROM_MOTOR_DATA_TYPE motor_data_type);
00140 
00141   std::vector<MessageChecker> msg_checkers_;
00142 };
00143 }  // namespace generic_updater
00144 
00145 /* For the emacs weenies in the crowd.
00146  Local Variables:
00147  c-basic-offset: 2
00148  End:
00149  */
00150 
00151 #endif /* MOTOR_DATA_CHECKER_HPP_ */


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