sr_edc_muscle.h
Go to the documentation of this file.
1 
25 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR_EDC_MUSCLE_H
26 #define SR_EDC_ETHERCAT_DRIVERS_SR_EDC_MUSCLE_H
27 
28 #include <ros_ethercat_hardware/ethercat_hardware.h>
31 #include <std_msgs/Int16.h>
32 #include <std_msgs/Float64MultiArray.h>
33 #include <sr_robot_msgs/SimpleMotorFlasher.h>
34 #include <pthread.h>
35 #include <bfd.h>
36 #include <boost/smart_ptr.hpp>
37 #include <map>
38 #include <vector>
39 #include <boost/assign.hpp>
40 #include <boost/algorithm/string.hpp>
41 #include <boost/algorithm/string/find_iterator.hpp>
42 
44 
45 #include <sr_robot_msgs/EthercatDebug.h>
46 
48 
49 extern "C"
50 {
52 }
53 
54 class SrEdcMuscle :
55  public SrEdc
56 {
57 public:
58  SrEdcMuscle();
59 
60  virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address);
61 
62  virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true);
63 
64  virtual void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer);
65 
66  virtual void packCommand(unsigned char *buffer, bool halt, bool reset);
67 
68  virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer);
69 
70 protected:
72  std::vector<boost::shared_ptr<rt_pub_int16_t> > realtime_pub_;
73 
76 
78  virtual void reinitialize_boards();
79 
88  virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id);
89 
90 private:
91  // std::string firmware_file_name;
92 
93  // counter for the number of empty buffer we're reading.
94  unsigned int zero_buffer_read;
95 
96  boost::shared_ptr<shadow_robot::SrMuscleHandLib<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
97  ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> > sr_hand_lib;
98 
103  int16_t cycle_count;
104 
107 };
108 
109 
110 /* For the emacs weenies in the crowd.
111 Local Variables:
112  c-basic-offset: 2
113 End:
114 */
115 
116 
117 #endif // SR_EDC_ETHERCAT_DRIVERS_SR_EDC_MUSCLE_H
118 
Definition: sr_edc.h:60
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::EthercatDebug > > debug_publisher
Debug real time publisher: publishes the raw ethercat data.
realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
Definition: sr_edc_muscle.h:71
virtual void reinitialize_boards()
This function will call the reinitialization function for the boards attached to the CAN bus...
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
Construct function, run at startup to set SyncManagers and FMMUs.
virtual void multiDiagnostics(vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
This function gives some diagnostics data.
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
Definition: sr_edc_muscle.h:72
int16_t cycle_count
This is a parent class for the ROS drivers for any Shadow Robot EtherCAT Dual CAN Slave...
virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
This functions receives data from the EtherCAT bus.
virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
unsigned int zero_buffer_read
Definition: sr_edc_muscle.h:94
boost::shared_ptr< shadow_robot::SrMuscleHandLib< ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND > > sr_hand_lib
Definition: sr_edc_muscle.h:97
boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
Extra analog inputs real time publisher (+ accelerometer and gyroscope)
Definition: sr_edc_muscle.h:75
virtual void packCommand(unsigned char *buffer, bool halt, bool reset)
packs the commands before sending them to the EtherCAT bus
SrEdcMuscle()
Constructor of the SrEdcMuscle driver.


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Mon Feb 28 2022 23:50:53