31 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H 32 #define SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H 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> 42 #include <boost/smart_ptr.hpp> 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> 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);
73 sr_robot_msgs::SimpleMotorFlasher::Response &res);
82 bool read_flash(
unsigned int offset,
unsigned int baddr);
172 void find_address_range(bfd *fd,
unsigned int *smallest_start_address,
unsigned int *biggest_end_address);
204 std::vector<std::string> splitted_string;
205 boost::split(splitted_string, full_path, boost::is_any_of(
"/"));
206 return splitted_string.back();
218 #endif // SR_EDC_ETHERCAT_DRIVERS_SR_EDC_H
unsigned int motor_being_flashed
ros::NodeHandle nh_tilde_
bfd_byte * binary_content
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.
static const unsigned int max_retry
realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
bool read_flash(unsigned int offset, unsigned int baddr)
Function that reads back 8 bytes from PIC18F program memory.
virtual void reinitialize_boards()=0
This function will call the reinitialization function for the boards attached to the CAN bus...
pthread_mutex_t producing
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.
ETHERCAT_CAN_BRIDGE_DATA can_message_
virtual void get_board_id_and_can_bus(int board_id, int *can_bus, unsigned int *board_can_id)=0
bool write_flash_data(unsigned int base_addr, unsigned int total_size)
ros::NodeHandle nodehandle_
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
void send_CAN_msg(int8u can_bus, int16u msg_id, int8u msg_length, int8u msg_data[], int timeout, bool *timedout)
void erase_flash()
Erase the PIC18F Flash memory.
void build_CAN_message(ETHERCAT_CAN_BRIDGE_DATA *message)
SrEdc()
Constructor of the SrEdc driver.
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.
bool read_content_from_object_file(bfd *fd, bfd_byte *content, unsigned int base_addr)
static std::string get_filename(std::string full_path)
std::string device_joint_prefix_
boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
Extra analog inputs real time publisher (+ accelerometer and gyroscope)
void find_address_range(bfd *fd, unsigned int *smallest_start_address, unsigned int *biggest_end_address)
ros::ServiceServer serviceServer
bool read_back_and_check_flash(unsigned int baddr, unsigned int total_size)