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


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Thu Aug 27 2015 15:16:54