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 00046 class MessageFromMotorChecker 00047 { 00048 public: 00049 MessageFromMotorChecker(int id) 00050 : motor_id_(id), received_(false) 00051 {}; 00052 00053 ~MessageFromMotorChecker() 00054 {}; 00055 00056 int motor_id_; 00057 virtual void set_received(); 00058 bool get_received(); 00059 00060 protected: 00061 bool received_; 00062 }; 00063 00064 class SlowMessageFromMotorChecker : public MessageFromMotorChecker 00065 { 00066 public: 00067 SlowMessageFromMotorChecker(int id); 00068 ~SlowMessageFromMotorChecker() 00069 {}; 00070 00071 boost::array<bool, MOTOR_SLOW_DATA_LAST + 1> slow_data_received; 00072 00073 virtual void set_received(FROM_MOTOR_SLOW_DATA_TYPE slow_data_type); 00074 }; 00075 00076 class MessageChecker 00077 { 00078 public: 00079 MessageChecker(FROM_MOTOR_DATA_TYPE msg_type) 00080 : msg_type(msg_type) 00081 {}; 00082 00083 ~MessageChecker() 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(boost::ptr_vector<shadow_joints::Joint> joints_vector, 00100 std::vector<UpdateConfig> initialization_configs_vector); 00101 ~MotorDataChecker(); 00102 00114 bool check_message(boost::ptr_vector<shadow_joints::Joint>::iterator joint_tmp, 00115 FROM_MOTOR_DATA_TYPE motor_data_type, int16u motor_slow_data_type); 00116 00124 void init(boost::ptr_vector<shadow_joints::Joint> joints_vector, 00125 std::vector<UpdateConfig> initialization_configs_vector); 00126 00127 protected: 00128 static const double timeout; 00129 ros::NodeHandle nh_tilde; 00130 ros::Timer check_timeout_timer; 00131 operation_mode::device_update_state::DeviceUpdateState update_state; 00132 ros::Duration init_max_duration; 00133 00134 void timer_callback(const ros::TimerEvent& event); 00135 bool is_everything_checked(); 00136 int find(FROM_MOTOR_DATA_TYPE motor_data_type); 00137 00138 std::vector<MessageChecker> msg_checkers_; 00139 }; 00140 00141 } 00142 00143 /* For the emacs weenies in the crowd. 00144 Local Variables: 00145 c-basic-offset: 2 00146 End: 00147 */ 00148 00149 #endif /* MOTOR_DATA_CHECKER_HPP_ */