00001 00027 #ifndef SR06_H 00028 #define SR06_H 00029 00030 #include <ethercat_hardware/ethercat_device.h> 00031 #include <sr_edc_ethercat_drivers/sr_edc.h> 00032 #include <realtime_tools/realtime_publisher.h> 00033 #include <std_msgs/Int16.h> 00034 #include <std_msgs/Float64MultiArray.h> 00035 #include <sr_robot_msgs/SimpleMotorFlasher.h> 00036 #include <pthread.h> 00037 #include <bfd.h> 00038 #include <boost/smart_ptr.hpp> 00039 #include <map> 00040 #include <boost/assign.hpp> 00041 #include <boost/algorithm/string.hpp> 00042 #include <boost/algorithm/string/find_iterator.hpp> 00043 00044 #include <sr_robot_lib/sr_motor_hand_lib.hpp> 00045 00046 #include <sr_robot_msgs/EthercatDebug.h> 00047 00048 #include <sr_external_dependencies/types_for_external.h> 00049 extern "C" 00050 { 00051 #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h> 00052 } 00053 00054 00055 class SR06 : public SrEdc 00056 { 00057 public: 00058 SR06(); 00059 ~SR06(); 00060 00061 void construct(EtherCAT_SlaveHandler *sh, int &start_address); 00062 int initialize(pr2_hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true); 00063 void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer); 00064 00065 void packCommand(unsigned char *buffer, bool halt, bool reset); 00066 bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer); 00067 00068 protected: 00069 00070 typedef realtime_tools::RealtimePublisher<std_msgs::Int16> rt_pub_int16_t; 00071 std::vector< boost::shared_ptr<rt_pub_int16_t> > realtime_pub_; 00072 00074 boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray> > extra_analog_inputs_publisher; 00075 00077 void reinitialize_boards(); 00078 00087 void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id); 00088 00089 private: 00090 00091 //std::string firmware_file_name; 00092 00094 unsigned int zero_buffer_read; 00095 00096 boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> > sr_hand_lib; 00097 00102 short cycle_count; 00103 00105 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> > debug_publisher; 00106 00107 00108 }; 00109 00110 00111 /* For the emacs weenies in the crowd. 00112 Local Variables: 00113 c-basic-offset: 2 00114 End: 00115 */ 00116 00117 00118 #endif /* SR06_H */ 00119