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

#include <sr06.h>

Inheritance diagram for SR06:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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.
void construct (EtherCAT_SlaveHandler *sh, int &start_address)
 Construct function, run at startup to set SyncManagers and FMMUs.
void erase_flash ()
 Erase the PIC18F Flash memory.
int initialize (pr2_hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
void multiDiagnostics (vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
 This function gives some diagnostics data.
void packCommand (unsigned char *buffer, bool halt, bool reset)
 packs the commands before sending them to the EtherCAT bus
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.
 SR06 ()
 Constructor of the SR06 driver.
bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 This functions receives data from the EtherCAT bus.
 ~SR06 ()
 Destructor of the SR06 driver.

Protected Types

typedef
realtime_tools::RealtimePublisher
< std_msgs::Int16
rt_pub_int16_t

Protected Attributes

int counter_
ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS data_
boost::shared_ptr
< realtime_tools::RealtimePublisher
< std_msgs::Float64MultiArray > > 
extra_analog_inputs_publisher
 Extra analog inputs real time publisher (+ accelerometer and gyroscope)
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
bool can_packet_acked
short cycle_count
boost::shared_ptr
< realtime_tools::RealtimePublisher
< sr_robot_msgs::EthercatDebug > > 
debug_publisher
 Debug real time publisher: publishes the raw ethercat data.
std::string firmware_file_name
bool flashing
unsigned int motor_being_flashed
unsigned int pos
pthread_mutex_t producing
ros::ServiceServer serviceServer
boost::shared_ptr
< shadow_robot::SrHandLib
sr_hand_lib
unsigned int zero_buffer_read
 counter for the number of empty buffer we're reading.

Static Private Attributes

static const unsigned short int device_pub_freq_const = 1000
static const unsigned short int max_iter_const = device_pub_freq_const / ros_pub_freq_const
static const unsigned int max_retry = 20
static const unsigned char nb_publish_by_unpack_const = (nb_sensors_const % max_iter_const) ? (nb_sensors_const / max_iter_const) + 1 : (nb_sensors_const / max_iter_const)
static const unsigned int nb_sensors_const = ETHERCAT_STATUS_DATA_SIZE/2
static const unsigned short int ros_pub_freq_const = 1000

Detailed Description

Definition at line 55 of file sr06.h.


Member Typedef Documentation

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

Definition at line 78 of file sr06.h.


Constructor & Destructor Documentation

Constructor of the SR06 driver.

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

Definition at line 126 of file sr06.cpp.

Destructor of the SR06 driver.

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

Definition at line 156 of file sr06.cpp.


Member Function Documentation

bool SR06::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 778 of file sr06.cpp.

void SR06::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 SR06 driver, put the sum of the size, same thing for the status.

Reimplemented from SR0X.

Definition at line 195 of file sr06.cpp.

void SR06::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 312 of file sr06.cpp.

void SR06::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 1060 of file sr06.cpp.

static std::string SR06::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 187 of file sr06.h.

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

Reimplemented from SR0X.

Definition at line 284 of file sr06.cpp.

void SR06::multiDiagnostics ( vector< diagnostic_msgs::DiagnosticStatus > &  vec,
unsigned char *  buffer 
) [virtual]

This function gives some diagnostics data.

This function provides diagnostics data that can be displayed by the runtime_monitor node. We use the mutliDiagnostics as it publishes the diagnostics for each motors.

Reimplemented from EthercatDevice.

Definition at line 633 of file sr06.cpp.

void SR06::packCommand ( unsigned char *  buffer,
bool  halt,
bool  reset 
) [virtual]

packs the commands before sending them to the EtherCAT bus

This is one of the most important functions of this driver. This function is called each millisecond (1 kHz freq) by the EthercatHardware::update() function in the controlLoop() of the pr2_etherCAT node.

This function is called with a buffer as a parameter, the buffer provided is where we write the commands to send via EtherCAT.

We just cast the buffer to our structure type, fill the structure with our data, then add the structure size to the buffer address to shift into memory and access the second command. The buffer has been allocated with command_size_ bytes, which is the sum of the two command size, so we have to put the two commands one next to the other. In fact we access the buffer using this kind of code :

  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND  *command = (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND *)buffer;
  ETHERCAT_CAN_BRIDGE_DATA                       *message = (ETHERCAT_CAN_BRIDGE_DATA *)(buffer + ETHERCAT_COMMAND_DATA_SIZE);

Reimplemented from EthercatDevice.

Definition at line 684 of file sr06.cpp.

bool SR06::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:
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 both are identical

Definition at line 1032 of file sr06.cpp.

bool SR06::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 1093 of file sr06.cpp.

bool SR06::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 378 of file sr06.cpp.

void SR06::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 986 of file sr06.cpp.

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 SR06::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 462 of file sr06.cpp.

bool SR06::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
) [virtual]

This functions receives data from the EtherCAT bus.

This function allows the driver to get the data present on the EtherCAT bus and intended for us.

It gives us access to the logical memory registered during the construct().

In order to be able to do differentials two buffers are kept, this_buffer is the actual data that has just been received and prev_buffer is the previous buffer received from the EtherCAT bus.

We access the data sent by PIC32 here using the same tricks we used in packCommand().

  ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *tbuffer = (ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS *)(this_buffer + command_size_);
  ETHERCAT_CAN_BRIDGE_DATA *can_data = (ETHERCAT_CAN_BRIDGE_DATA *)(this_buffer + command_size_ + ETHERCAT_STATUS_DATA_SIZE);
Parameters:
this_bufferThe data just being received by EtherCAT
prev_bufferThe previous data received by EtherCAT

Reimplemented from EthercatDevice.

Definition at line 873 of file sr06.cpp.

bool SR06::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 1129 of file sr06.cpp.


Member Data Documentation

bfd_byte* SR06::binary_content [private]

Definition at line 100 of file sr06.h.

int SR06::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 119 of file sr06.h.

ETHERCAT_CAN_BRIDGE_DATA SR06::can_message_ [private]

Definition at line 97 of file sr06.h.

Definition at line 98 of file sr06.h.

Definition at line 99 of file sr06.h.

int SR06::counter_ [protected]

Definition at line 74 of file sr06.h.

short SR06::cycle_count [private]

a counter used to publish the tactiles at 100Hz: count 10 cycles, then reset the cycle_count to 0.

Definition at line 113 of file sr06.h.

ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS SR06::data_ [protected]

Definition at line 75 of file sr06.h.

boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> > SR06::debug_publisher [private]

Debug real time publisher: publishes the raw ethercat data.

Definition at line 116 of file sr06.h.

const unsigned short int SR06::device_pub_freq_const = 1000 [static, private]

Definition at line 90 of file sr06.h.

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

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

Definition at line 82 of file sr06.h.

std::string SR06::firmware_file_name [private]

Definition at line 92 of file sr06.h.

bool SR06::flashing [private]

Definition at line 96 of file sr06.h.

const unsigned short int SR06::max_iter_const = device_pub_freq_const / ros_pub_freq_const [static, private]

Definition at line 88 of file sr06.h.

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

Definition at line 87 of file sr06.h.

unsigned int SR06::motor_being_flashed [private]

Definition at line 102 of file sr06.h.

Definition at line 91 of file sr06.h.

const unsigned int SR06::nb_sensors_const = ETHERCAT_STATUS_DATA_SIZE/2 [static, private]

Definition at line 86 of file sr06.h.

Definition at line 76 of file sr06.h.

unsigned int SR06::pos [private]

Definition at line 101 of file sr06.h.

pthread_mutex_t SR06::producing [private]

Definition at line 93 of file sr06.h.

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

Definition at line 79 of file sr06.h.

const unsigned short int SR06::ros_pub_freq_const = 1000 [static, private]

Definition at line 89 of file sr06.h.

Definition at line 94 of file sr06.h.

boost::shared_ptr<shadow_robot::SrHandLib> SR06::sr_hand_lib [private]

Definition at line 107 of file sr06.h.

unsigned int SR06::zero_buffer_read [private]

counter for the number of empty buffer we're reading.

Definition at line 105 of file sr06.h.


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


sr_edc_ethercat_drivers
Author(s): Yann Sionneau, Ugo Cupcic / ugo@shadowrobot.com, software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:03:32