Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
SrEdc Class Reference

#include <sr_edc.h>

Inheritance diagram for SrEdc:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void build_CAN_message (ETHERCAT_CAN_BRIDGE_DATA *message)
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.
virtual void construct (EtherCAT_SlaveHandler *sh, int &start_address)
 Construct function, run at startup to set SyncManagers and FMMUs.
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.
void erase_flash ()
 Erase the PIC18F Flash memory.
virtual int initialize (pr2_hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
bool read_flash (unsigned int offset, unsigned int baddr)
 Function that reads back 8 bytes from PIC18F program memory.
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.
 SrEdc ()
 Constructor of the SrEdc driver.
virtual ~SrEdc ()
 Destructor of the SrEdc driver.

Protected Types

typedef
realtime_tools::RealtimePublisher
< std_msgs::Int16 > 
rt_pub_int16_t

Protected Member Functions

virtual void get_board_id_and_can_bus (int board_id, int *can_bus, unsigned int *board_can_id)=0
virtual void reinitialize_boards ()=0
 This function will call the reinitialization function for the boards attached to the CAN bus.

Protected Attributes

bool can_packet_acked
int counter_
boost::shared_ptr
< realtime_tools::RealtimePublisher
< std_msgs::Float64MultiArray > > 
extra_analog_inputs_publisher
 Extra analog inputs real time publisher (+ accelerometer and gyroscope)
bool flashing
ros::NodeHandle nodehandle_
std::vector< boost::shared_ptr
< rt_pub_int16_t > > 
realtime_pub_

Private Member Functions

void find_address_range (bfd *fd, unsigned int *smallest_start_address, unsigned int *biggest_end_address)
bool read_back_and_check_flash (unsigned int baddr, unsigned int total_size)
bool read_content_from_object_file (bfd *fd, bfd_byte *content, unsigned int base_addr)
void send_CAN_msg (int8u can_bus, int16u msg_id, int8u msg_length, int8u msg_data[], int timeout, bool *timedout)
bool write_flash_data (unsigned int base_addr, unsigned int total_size)

Static Private Member Functions

static std::string get_filename (std::string full_path)

Private Attributes

bfd_byte * binary_content
int can_bus_
 We're using 2 can busses, so can_bus_ is 1 for motors 0 to 9 and 2 for motors 10 to 19.
ETHERCAT_CAN_BRIDGE_DATA can_message_
bool can_message_sent
unsigned int motor_being_flashed
unsigned int pos
pthread_mutex_t producing
ros::ServiceServer serviceServer

Static Private Attributes

static const unsigned int max_retry = 20

Detailed Description

Definition at line 61 of file sr_edc.h.


Member Typedef Documentation

typedef realtime_tools::RealtimePublisher<std_msgs::Int16> SrEdc::rt_pub_int16_t [protected]

Reimplemented in SR06, SR08, and SrEdcMuscle.

Definition at line 83 of file sr_edc.h.


Constructor & Destructor Documentation

Constructor of the SrEdc driver.

This is the Constructor of the driver. We initialize a few boolean values, a mutex and create the Bootloading service.

Definition at line 122 of file sr_edc.cpp.

SrEdc::~SrEdc ( ) [virtual]

Destructor of the SrEdc driver.

This is the Destructor of the driver. it frees the FMMUs and SyncManagers which have been allocated during the construct.

Definition at line 143 of file sr_edc.cpp.


Member Function Documentation

void SrEdc::build_CAN_message ( ETHERCAT_CAN_BRIDGE_DATA *  message)

Definition at line 623 of file sr_edc.cpp.

bool SrEdc::can_data_is_ack ( ETHERCAT_CAN_BRIDGE_DATA *  packet)

This function checks if the can packet in the unpackState() this_buffer is an ACK.

This function checks several things on the can packet in this_buffer, it compares it with the can_message_ private member in several ways (SID, length, data) to check if it's an ACK.

Parameters:
packetThe packet from this_buffer of unpackState() that we want to check if it's an ACK
Returns:
Returns true if packet is an ACK of can_message_ packet.

Definition at line 674 of file sr_edc.cpp.

void SrEdc::construct ( EtherCAT_SlaveHandler *  sh,
int &  start_address 
) [virtual]

Construct function, run at startup to set SyncManagers and FMMUs.

The role of this function is to setup the SyncManagers and the FMMUs used by this EtherCAT slave. This slave is using two Mailboxes on two different memory areas.

Here we are setting up the way of communicating between ROS and the PIC32 using the EtherCAT protocol.

We communicate using Shared Memory areas.

The FMMUs are usefull to map the logical memory used by ROS to the Physical memory of the EtherCAT slave chip (ET1200 chip). So that the chip receiving the packet will know that the data at address 0x10000 is in reality to be written at physical address 0x1000 of the chip memory for example. It is the mapping between the EtherCAT bus address space and each slave's chip own memory address space.

The SyncManagers are usefull to give a safe way of accessing this Shared Memory, using a consumer / producer model. There are features like interrupts to tell the consumer that there is something to consume or to tell the producer that the Mailbox is empty and then ready to receive a new message.

  • One Mailbox contains the commands, written by ROS, read by the PIC32
  • One Mailbox contains the status, written back by the PIC32, read by ROS

That's basically one Mailbox for upstream and one Mailbox for downstream.

  • The first Mailbox contains in fact two commands, one is the torque demand, the other is a CAN command used in CAN_DIRECT_MODE to communicate with the SimpleMotor for test purposes, or to reflash a new firmware in bootloading mode. This Mailbox is at logicial address 0x10000 and mapped via a FMMU to physical address 0x1000 (the first address of user memory)
  • The second Mailbox contains in fact two status, they are the response of the two previously described commands. One is the status containing the joints data, sensor data, finger tips data and motor data. The other is the can command response in CAN_DIRECT_MODE. When doing a flashing in bootloading mode this is usually an acknowledgment from the bootloader. This Mailbox is at logical address 0x10038 and mapped via a FMMU to physical address 0x1038.

This function sets the two private members command_size_ and status_size_ to be the size of each Mailbox. It is important for these numbers to be accurate since they are used by the EthercatHardware class when manipulating the buffers. If you need to have several commands like in this SrEdc driver, put the sum of the size, same thing for the status.

Reimplemented from SR0X.

Reimplemented in SR06, SR08, and SrEdcMuscle.

Definition at line 182 of file sr_edc.cpp.

void SrEdc::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 
) [virtual]

Construct function, run at startup to set SyncManagers and FMMUs.

The role of this function is to setup the SyncManagers and the FMMUs used by this EtherCAT slave. This slave is using two Mailboxes on two different memory areas.

Here we are setting up the way of communicating between ROS and the PIC32 using the EtherCAT protocol.

We communicate using Shared Memory areas.

The FMMUs are usefull to map the logical memory used by ROS to the Physical memory of the EtherCAT slave chip (ET1200 chip). So that the chip receiving the packet will know that the data at address 0x10000 is in reality to be written at physical address 0x1000 of the chip memory for example. It is the mapping between the EtherCAT bus address space and each slave's chip own memory address space.

The SyncManagers are usefull to give a safe way of accessing this Shared Memory, using a consumer / producer model. There are features like interrupts to tell the consumer that there is something to consume or to tell the producer that the Mailbox is empty and then ready to receive a new message.

  • One Mailbox contains the commands, written by ROS, read by the PIC32
  • One Mailbox contains the status, written back by the PIC32, read by ROS

That's basically one Mailbox for upstream and one Mailbox for downstream.

  • The first Mailbox contains in fact two commands, one is the torque demand, the other is a CAN command used in CAN_DIRECT_MODE to communicate with the SimpleMotor for test purposes, or to reflash a new firmware in bootloading mode. This Mailbox is at logicial address 0x10000 and mapped via a FMMU to physical address 0x1000 (the first address of user memory)
  • The second Mailbox contains in fact two status, they are the response of the two previously described commands. One is the status containing the joints data, sensor data, finger tips data and motor data. The other is the can command response in CAN_DIRECT_MODE. When doing a flashing in bootloading mode this is usually an acknowledgment from the bootloader. This Mailbox is at logical address 0x10038 and mapped via a FMMU to physical address 0x1038.

This function sets the two private members command_size_ and status_size_ to be the size of each Mailbox. It is important for these numbers to be accurate since they are used by the EthercatHardware class when manipulating the buffers. If you need to have several commands like in this SR06 driver, put the sum of the size, same thing for the status.

Definition at line 220 of file sr_edc.cpp.

void SrEdc::erase_flash ( void  )

Erase the PIC18F Flash memory.

This function fills the can_message_ struct with a CAN message which tells the bootloader of the PIC18F to erase its Flash memory

Definition at line 321 of file sr_edc.cpp.

void SrEdc::find_address_range ( bfd *  fd,
unsigned int *  smallest_start_address,
unsigned int *  biggest_end_address 
) [private]

Look for the start and end address of every section in the hex file, to detect the lowest and highest address of the data we need to write in the PIC's flash. The sections starting at an address higher than 0x7fff will be ignored as they are not proper "code memory" firmware (they can contain the CONFIG bits of the microcontroller, which we don't want to write here) To understand the structure (sections) of the object file containing the firmware (usually a .hex) the following commands can be useful:

 objdump -x simplemotor.hex 
 objdump -s simplemotor.hex 
Parameters:
fdpointer to a bfd file structure
smallest_start_addressthe lowest address found is returned through this pointer
biggest_end_addressthe highest address found is returned through this pointer

Definition at line 826 of file sr_edc.cpp.

virtual void SrEdc::get_board_id_and_can_bus ( int  board_id,
int *  can_bus,
unsigned int *  board_can_id 
) [protected, pure virtual]

Given the identifier for a certain board (motor board/ muscle driver) determines the right value for the CAN bus and the ID of the board in that CAN bus.

Parameters:
board_idthe unique identifier for the board
can_buspointer to the can bus number we want to determine
board_can_idpointer to the board id we want to determine

Implemented in SR06, SR08, and SrEdcMuscle.

static std::string SrEdc::get_filename ( std::string  full_path) [inline, static, private]

Extract the filename from the full path.

Parameters:
full_pathThe full path.
Returns:
the filename.

Definition at line 193 of file sr_edc.h.

int SrEdc::initialize ( pr2_hardware_interface::HardwareInterface hw,
bool  allow_unprogrammed = true 
) [virtual]

Reimplemented from SR0X.

Reimplemented in SR06, SR08, and SrEdcMuscle.

Definition at line 308 of file sr_edc.cpp.

bool SrEdc::read_back_and_check_flash ( unsigned int  baddr,
unsigned int  total_size 
) [private]

Read back the firmware from the flash of the PIC, and checks it against the data read from the object (.hex) file

Parameters:
baddrthe base address of the code (the lowest address to be written on the flash)
total_sizethe size in bytes of the code to write
Returns:
true if both are identical

Definition at line 798 of file sr_edc.cpp.

bool SrEdc::read_content_from_object_file ( bfd *  fd,
bfd_byte *  content,
unsigned int  base_addr 
) [private]

Reads the content from the object (.hex) file and stores it in a previously reserved memory space

Parameters:
fdpointer to a bfd file structure
contenta pointer to the memory space where we want to store the firmware
base_addrthe base address of the code (the lowest address to be written on the flash)
Returns:
true if the reading succeeds

Definition at line 859 of file sr_edc.cpp.

bool SrEdc::read_flash ( unsigned int  offset,
unsigned int  baddr 
)

Function that reads back 8 bytes from PIC18F program memory.

Flash memory is the program memory on the PIC18F This function is here to read back what we flashed into the PIC18F To check that there was no flashing transmission or writting error during the Flashing process. 8 bytes will be read, from address baddr + offset This function will fill the can_message_ structure with the correct value to allow the packCommand() function to send the correct etherCAT message to the PIC32 which will then send the correct CAN message to the PIC18F

Parameters:
offsetThe position of the 8 bytes we want to read, relative to the base address
baddrthe base address
Returns:
Returns true if the command has timed out, false if the command was properly acknowledged

Definition at line 387 of file sr_edc.cpp.

virtual void SrEdc::reinitialize_boards ( ) [protected, pure virtual]

This function will call the reinitialization function for the boards attached to the CAN bus.

Implemented in SR06, SR08, and SrEdcMuscle.

void SrEdc::send_CAN_msg ( int8u  can_bus,
int16u  msg_id,
int8u  msg_length,
int8u  msg_data[],
int  timeout,
bool *  timedout 
) [private]

Contains the common procedure to send a CAN message (i.e. write it in the global struct from which it is read, added to the next ethercat frame, and sent) and wait for the can_packet_acked flag to be set

Parameters:
can_buswhich of the 2 CAN buses (0 or 1) wil be used
msg_idid of the CAN message
msg_lengththe length in bytes of msg_data
msg_datadata of the CAN message
timeouttime max (in ms) to wait for the can_packet_acked flag to be set
timedoutif true, the can_packet_acked flag wasn't set before the timeout

Definition at line 752 of file sr_edc.cpp.

bool SrEdc::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.

This function is a ROS Service, aimed at flashing a new firmware into the PIC18F of a SimpleMotor board through a CAN bootloader protocol.

The CAN bootloader allows for several commands to be executed : read_flash, erase_flash, write_flash, reboot, read_version

This service will fill a can_message_ structure and then switch a few boolean values to "false" in order to trigger the message to be sent by the SRXX::packCommand() function. And then repeat the process for another message, and so on.

This service will first read all the sections of the firmware using libbfd and find out the lowest and highest addresses containing code. Then it will allocate an array to contain the firmware's code. The size is (highest_addr - lowest_addr). The bfd library provides functions to manage object files more easily. To better understand some of the concepts used below, the following link can be useful: http://www.delorie.com/gnu/docs/binutils/ld_7.html The use of the following commands can also help to understand the structure of the object file containing the firmware

 objdump -x simplemotor.hex 
 objdump -s simplemotor.hex 
  • Then it will send a MAGIC PACKET command to the PIC18F which will make it reboot in bootloader mode (regardless of whether it was already in bootloader mode or whether it was running the SimpleMotor code)
  • Then it will send an ERASE_FLASH command to the PIC18F.
  • Then it will send a WRITE_FLASH_ADDRESS_COMMAND to tell the PIC18F where we wanna write, and then 4 WRITE_FLASH_DATA commands (we write by blocks of 32 bytes). This process is repeated untill we've written all the firmware code, padding with 0x00 bytes in the end if the size is not a multiple of 32 bytes. The process starts at address (lowest_addr) and ends at (hiest_addr) + a few padding bytes if necessary.

You can call this service using this command :

 rosservice call SimpleMotorFlasher "/home/hand/simplemotor.hex" 8 

This will flash the "simplemotor.hex" firmware to the motor 8

Parameters:
reqThe Request, contains the ID of the motor we want to flash via req.motor_id, and the path of the firmware to flash in req.firmware
resThe Response, it is always SUCCESS for now.
Returns:
This returns always true, the real return value is in the res parameter

Definition at line 471 of file sr_edc.cpp.

bool SrEdc::write_flash_data ( unsigned int  base_addr,
unsigned int  total_size 
) [private]

Writes the code previously read from the hex file to the flash memory of the PIC

Parameters:
base_addrthe base address of the code (the lowest address to be written on the flash)
total_sizethe size in bytes of the code to write
Returns:
true if the writing process succeeds

Definition at line 895 of file sr_edc.cpp.


Member Data Documentation

bfd_byte* SrEdc::binary_content [private]

Definition at line 119 of file sr_edc.h.

int SrEdc::can_bus_ [private]

We're using 2 can busses, so can_bus_ is 1 for motors 0 to 9 and 2 for motors 10 to 19.

Definition at line 125 of file sr_edc.h.

ETHERCAT_CAN_BRIDGE_DATA SrEdc::can_message_ [private]

Definition at line 117 of file sr_edc.h.

bool SrEdc::can_message_sent [private]

Definition at line 118 of file sr_edc.h.

bool SrEdc::can_packet_acked [protected]

Definition at line 90 of file sr_edc.h.

int SrEdc::counter_ [protected]

Definition at line 80 of file sr_edc.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray> > SrEdc::extra_analog_inputs_publisher [protected]

Extra analog inputs real time publisher (+ accelerometer and gyroscope)

Reimplemented in SR06, SR08, and SrEdcMuscle.

Definition at line 87 of file sr_edc.h.

bool SrEdc::flashing [protected]

Definition at line 89 of file sr_edc.h.

const unsigned int SrEdc::max_retry = 20 [static, private]

Definition at line 107 of file sr_edc.h.

unsigned int SrEdc::motor_being_flashed [private]

Definition at line 121 of file sr_edc.h.

Definition at line 81 of file sr_edc.h.

unsigned int SrEdc::pos [private]

Definition at line 120 of file sr_edc.h.

pthread_mutex_t SrEdc::producing [private]

Definition at line 113 of file sr_edc.h.

std::vector< boost::shared_ptr<rt_pub_int16_t> > SrEdc::realtime_pub_ [protected]

Reimplemented in SR06, SR08, and SrEdcMuscle.

Definition at line 84 of file sr_edc.h.

Definition at line 114 of file sr_edc.h.


The documentation for this class was generated from the following files:


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