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


sr_edc_ethercat_drivers
Author(s): Ugo Cupcic, Yann Sionneau, Toni Oliver
autogenerated on Tue Oct 13 2020 04:02:02