sr_edc.h
Go to the documentation of this file.
1 
31 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H
32 #define SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H
33 
34 #include <ros_ethercat_hardware/ethercat_hardware.h>
37 #include <std_msgs/Int16.h>
38 #include <std_msgs/Float64MultiArray.h>
39 #include <sr_robot_msgs/SimpleMotorFlasher.h>
40 #include <pthread.h>
41 #include <bfd.h>
42 #include <boost/smart_ptr.hpp>
43 #include <map>
44 #include <string>
45 #include <vector>
46 #include <boost/assign.hpp>
47 #include <boost/algorithm/string.hpp>
48 #include <boost/algorithm/string/find_iterator.hpp>
49 #include <sr_robot_msgs/EthercatDebug.h>
50 
52 
53 extern "C"
54 {
57 }
58 
59 
60 class SrEdc :
61  public SR0X
62 {
63 public:
64  SrEdc();
65 
66  virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address, unsigned int ethercat_command_data_size,
67  unsigned int ethercat_status_data_size, unsigned int ethercat_can_bridge_data_size,
68  unsigned int ethercat_command_data_address, unsigned int ethercat_status_data_address,
69  unsigned int ethercat_can_bridge_data_command_address,
70  unsigned int ethercat_can_bridge_data_status_address);
71 
72  bool simple_motor_flasher(sr_robot_msgs::SimpleMotorFlasher::Request &req,
73  sr_robot_msgs::SimpleMotorFlasher::Response &res);
74 
75  void build_CAN_message(ETHERCAT_CAN_BRIDGE_DATA *message);
76 
77  bool can_data_is_ack(ETHERCAT_CAN_BRIDGE_DATA *packet);
78 
79  void erase_flash();
80 
81  // bool read_flash(unsigned int offset, unsigned char baddrl, unsigned char baddrh, unsigned char baddru);
82  bool read_flash(unsigned int offset, unsigned int baddr);
83 
84 protected:
85  int counter_;
88 
90  std::vector<boost::shared_ptr<rt_pub_int16_t> > realtime_pub_;
91 
94 
95  bool flashing;
97 
98  std::string device_id_;
99  std::string device_joint_prefix_;
100 
102  virtual void reinitialize_boards() = 0;
103 
112  virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id) = 0;
113 
114 private:
115  // static const unsigned int nb_sensors_const;
116  static const unsigned int max_retry;
117  // static const unsigned short int max_iter_const;
118  // static const unsigned short int ros_pub_freq_const;
119  // static const unsigned short int device_pub_freq_const;
120  // static const unsigned char nb_publish_by_unpack_const;
121  // std::string firmware_file_name;
122  pthread_mutex_t producing;
124 
125 
126  ETHERCAT_CAN_BRIDGE_DATA can_message_;
128  bfd_byte *binary_content; // buffer containing the binary content to be flashed
129  unsigned int pos; // position in binary_content buffer
130  unsigned int motor_being_flashed;
131 
132 
133  // We're using 2 can busses, so can_bus_ is 1 for motors 0 to 9 and 2 for motors 10 to 19
134  int can_bus_;
135 
147  void send_CAN_msg(int8u can_bus, int16u msg_id, int8u msg_length, int8u msg_data[], int timeout, bool *timedout);
148 
157  bool read_back_and_check_flash(unsigned int baddr, unsigned int total_size);
158 
172  void find_address_range(bfd *fd, unsigned int *smallest_start_address, unsigned int *biggest_end_address);
173 
183  bool read_content_from_object_file(bfd *fd, bfd_byte *content, unsigned int base_addr);
184 
193  bool write_flash_data(unsigned int base_addr, unsigned int total_size);
194 
202  static inline std::string get_filename(std::string full_path)
203  {
204  std::vector<std::string> splitted_string;
205  boost::split(splitted_string, full_path, boost::is_any_of("/"));
206  return splitted_string.back();
207  }
208 };
209 
210 
211 /* For the emacs weenies in the crowd.
212 Local Variables:
213  c-basic-offset: 2
214 End:
215 */
216 
217 
218 #endif // SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H
Definition: sr_edc.h:60
unsigned short int16u
unsigned int motor_being_flashed
Definition: sr_edc.h:130
ros::NodeHandle nh_tilde_
Definition: sr_edc.h:87
bfd_byte * binary_content
Definition: sr_edc.h:128
bool simple_motor_flasher(sr_robot_msgs::SimpleMotorFlasher::Request &req, sr_robot_msgs::SimpleMotorFlasher::Response &res)
ROS Service that flashes a new firmware into a SimpleMotor board.
Definition: sr_edc.cpp:458
static const unsigned int max_retry
Definition: sr_edc.h:116
realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
Definition: sr_edc.h:89
int counter_
Definition: sr_edc.h:85
bool read_flash(unsigned int offset, unsigned int baddr)
Function that reads back 8 bytes from PIC18F program memory.
Definition: sr_edc.cpp:375
virtual void reinitialize_boards()=0
This function will call the reinitialization function for the boards attached to the CAN bus...
pthread_mutex_t producing
Definition: sr_edc.h:122
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address, unsigned int ethercat_command_data_size, unsigned int ethercat_status_data_size, unsigned int ethercat_can_bridge_data_size, unsigned int ethercat_command_data_address, unsigned int ethercat_status_data_address, unsigned int ethercat_can_bridge_data_command_address, unsigned int ethercat_can_bridge_data_status_address)
Construct function, run at startup to set SyncManagers and FMMUs.
Definition: sr_edc.cpp:167
unsigned char int8u
bool can_packet_acked
Definition: sr_edc.h:96
ETHERCAT_CAN_BRIDGE_DATA can_message_
Definition: sr_edc.h:126
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)=0
bool can_message_sent
Definition: sr_edc.h:127
bool write_flash_data(unsigned int base_addr, unsigned int total_size)
Definition: sr_edc.cpp:906
ros::NodeHandle nodehandle_
Definition: sr_edc.h:86
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
Definition: sr_edc.h:90
void send_CAN_msg(int8u can_bus, int16u msg_id, int8u msg_length, int8u msg_data[], int timeout, bool *timedout)
Definition: sr_edc.cpp:750
void erase_flash()
Erase the PIC18F Flash memory.
Definition: sr_edc.cpp:308
void build_CAN_message(ETHERCAT_CAN_BRIDGE_DATA *message)
Definition: sr_edc.cpp:615
SrEdc()
Constructor of the SrEdc driver.
Definition: sr_edc.cpp:120
Generic driver for a Shadow Robot EtherCAT Slave. SR06 inherits from this class.
bool can_data_is_ack(ETHERCAT_CAN_BRIDGE_DATA *packet)
This function checks if the can packet in the unpackState() this_buffer is an ACK.
Definition: sr_edc.cpp:668
unsigned int pos
Definition: sr_edc.h:129
bool read_content_from_object_file(bfd *fd, bfd_byte *content, unsigned int base_addr)
Definition: sr_edc.cpp:867
int can_bus_
Definition: sr_edc.h:134
Definition: sr0x.h:32
static std::string get_filename(std::string full_path)
Definition: sr_edc.h:202
std::string device_joint_prefix_
Definition: sr_edc.h:99
std::string device_id_
Definition: sr_edc.h:98
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.h:93
void find_address_range(bfd *fd, unsigned int *smallest_start_address, unsigned int *biggest_end_address)
Definition: sr_edc.cpp:830
ros::ServiceServer serviceServer
Definition: sr_edc.h:123
bool flashing
Definition: sr_edc.h:95
bool read_back_and_check_flash(unsigned int baddr, unsigned int total_size)
Definition: sr_edc.cpp:797


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