Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
SR06 Class Reference

#include <sr06.h>

Inheritance diagram for SR06:
Inheritance graph
[legend]

Public Member Functions

virtual void construct (EtherCAT_SlaveHandler *sh, int &start_address)
 Construct function, run at startup to set SyncManagers and FMMUs. More...
 
virtual int initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
 
virtual void multiDiagnostics (vector< diagnostic_msgs::DiagnosticStatus > &vec, unsigned char *buffer)
 This function gives some diagnostics data. More...
 
virtual void packCommand (unsigned char *buffer, bool halt, bool reset)
 packs the commands before sending them to the EtherCAT bus More...
 
 SR06 ()
 Constructor of the SR06 driver. More...
 
virtual bool unpackState (unsigned char *this_buffer, unsigned char *prev_buffer)
 This functions receives data from the EtherCAT bus. More...
 
- Public Member Functions inherited from SrEdc
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. More...
 
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. More...
 
void erase_flash ()
 Erase the PIC18F Flash memory. More...
 
bool read_flash (unsigned int offset, unsigned int baddr)
 Function that reads back 8 bytes from PIC18F program memory. More...
 
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. More...
 
 SrEdc ()
 Constructor of the SrEdc driver. More...
 

Protected Types

typedef realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
 
- Protected Types inherited from SrEdc
typedef realtime_tools::RealtimePublisher< std_msgs::Int16 > rt_pub_int16_t
 
- Protected Types inherited from SR0X
enum  {
  MODE_OFF = 0x00, MODE_ENABLE = (1 << 0), MODE_CURRENT = (1 << 1), MODE_SAFETY_RESET = (1 << 4),
  MODE_SAFETY_LOCKOUT = (1 << 5), MODE_UNDERVOLTAGE = (1 << 6), MODE_RESET = (1 << 7)
}
 
enum  { EC_PRODUCT_ID_BRIDGE = 0, EC_PRODUCT_ID_SHADOWCAN = 2, EC_PRODUCT_ID_DUALMOTOR = 3 }
 

Protected Member Functions

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

Protected Attributes

boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Float64MultiArray > > extra_analog_inputs_publisher
 Extra analog inputs real time publisher (+ accelerometer and gyroscope) More...
 
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
 
- Protected Attributes inherited from SrEdc
bool can_packet_acked
 
int counter_
 
std::string device_id_
 
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) More...
 
bool flashing
 
ros::NodeHandle nh_tilde_
 
ros::NodeHandle nodehandle_
 
std::vector< boost::shared_ptr< rt_pub_int16_t > > realtime_pub_
 
- Protected Attributes inherited from SR0X
uint8_t board_major_
 
uint8_t board_minor_
 
int command_base_
 
int device_offset_
 
uint8_t fw_major_
 
uint8_t fw_minor_
 
int level_
 
string reason_
 
int status_base_
 

Private Attributes

int16_t cycle_count
 
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::EthercatDebug > > debug_publisher
 Debug real time publisher: publishes the raw ethercat data. More...
 
boost::shared_ptr< shadow_robot::SrMotorHandLib< ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND > > sr_hand_lib
 
unsigned int zero_buffer_read
 

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 72 of file sr06.h.

Constructor & Destructor Documentation

SR06::SR06 ( )

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 78 of file sr06.cpp.

Member Function Documentation

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.

Definition at line 125 of file sr06.cpp.

void SR06::get_board_id_and_can_bus ( int  board_id,
int *  can_bus,
unsigned int *  board_can_id 
)
protectedvirtual

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

Implements SrEdc.

Definition at line 424 of file sr06.cpp.

int SR06::initialize ( hardware_interface::HardwareInterface *  hw,
bool  allow_unprogrammed = true 
)
virtual

Reimplemented from SR0X.

Definition at line 138 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.

Definition at line 174 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 ros_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);

Definition at line 226 of file sr06.cpp.

void SR06::reinitialize_boards ( )
protectedvirtual

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

Implements SrEdc.

Definition at line 418 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

Definition at line 292 of file sr06.cpp.

Member Data Documentation

int16_t 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 104 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 107 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 76 of file sr06.h.

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

Definition at line 73 of file sr06.h.

boost::shared_ptr<shadow_robot::SrMotorHandLib<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> > SR06::sr_hand_lib
private

Definition at line 98 of file sr06.h.

unsigned int SR06::zero_buffer_read
private

Definition at line 95 of file sr06.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 Tue Oct 13 2020 04:02:02