sr08.h
Go to the documentation of this file.
00001 
00027 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR08_H
00028 #define SR_EDC_ETHERCAT_DRIVERS_SR08_H
00029 
00030 #include <ros_ethercat_hardware/ethercat_hardware.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 <vector>
00041 #include <boost/assign.hpp>
00042 #include <boost/algorithm/string.hpp>
00043 #include <boost/algorithm/string/find_iterator.hpp>
00044 
00045 #include <sr_robot_lib/sr_motor_hand_lib.hpp>
00046 
00047 #include <sr_robot_msgs/EthercatDebug.h>
00048 
00049 #include <sr_external_dependencies/types_for_external.h>
00050 
00051 extern "C"
00052 {
00053 #include <sr_external_dependencies/external/0230_palm_edc_TS/0230_palm_edc_ethercat_protocol.h>
00054 }
00055 
00056 class SR08 :
00057         public SrEdc
00058 {
00059 public:
00060   SR08();
00061 
00062   virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address);
00063 
00064   virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true);
00065 
00066   virtual void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer);
00067 
00068   virtual void packCommand(unsigned char *buffer, bool halt, bool reset);
00069 
00070   virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer);
00071 
00072 protected:
00073   typedef realtime_tools::RealtimePublisher<std_msgs::Int16> rt_pub_int16_t;
00074   std::vector<boost::shared_ptr<rt_pub_int16_t> > realtime_pub_;
00075 
00077   boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray> > extra_analog_inputs_publisher;
00078 
00080   virtual void reinitialize_boards();
00081 
00090   virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id);
00091 
00092 private:
00093   // std::string                      firmware_file_name;
00094 
00095   // counter for the number of empty buffer we're reading.
00096   unsigned int zero_buffer_read;
00097 
00098   boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS,
00099           ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND> > sr_hand_lib;
00100 
00105   int16_t cycle_count;
00106 
00108   boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> > debug_publisher;
00109 };
00110 
00111 
00112 /* For the emacs weenies in the crowd.
00113 Local Variables:
00114    c-basic-offset: 2
00115 End:
00116  */
00117 
00118 
00119 #endif  // SR_EDC_ETHERCAT_DRIVERS_SR08_H
00120 


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:31