#include <sr06.h>
Public Member Functions | |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
Construct function, run at startup to set SyncManagers and FMMUs. | |
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. | |
virtual void | packCommand (unsigned char *buffer, bool halt, bool reset) |
packs the commands before sending them to the EtherCAT bus | |
SR06 () | |
Constructor of the SR06 driver. | |
virtual bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
This functions receives data from the EtherCAT bus. | |
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) |
virtual void | reinitialize_boards () |
This function will call the reinitialization function for the boards attached to the CAN bus. | |
Protected Attributes | |
boost::shared_ptr < realtime_tools::RealtimePublisher < std_msgs::Float64MultiArray > > | extra_analog_inputs_publisher |
Extra analog inputs real time publisher (+ accelerometer and gyroscope) | |
std::vector< boost::shared_ptr < rt_pub_int16_t > > | realtime_pub_ |
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. | |
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 |
typedef realtime_tools::RealtimePublisher<std_msgs::Int16> SR06::rt_pub_int16_t [protected] |
SR06::SR06 | ( | ) |
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.
That's basically one Mailbox for upstream and one Mailbox for downstream.
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 EthercatDevice.
void SR06::get_board_id_and_can_bus | ( | int | board_id, |
int * | can_bus, | ||
unsigned int * | board_can_id | ||
) | [protected, 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.
board_id | the unique identifier for the board |
can_bus | pointer to the can bus number we want to determine |
board_can_id | pointer to the board id we want to determine |
Implements SrEdc.
int SR06::initialize | ( | hardware_interface::HardwareInterface * | hw, |
bool | allow_unprogrammed = true |
||
) | [virtual] |
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.
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);
Reimplemented from EthercatDevice.
void SR06::reinitialize_boards | ( | ) | [protected, virtual] |
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);
this_buffer | The data just being received by EtherCAT |
prev_buffer | The previous data received by EtherCAT |
Reimplemented from EthercatDevice.
int16_t SR06::cycle_count [private] |
boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::EthercatDebug> > SR06::debug_publisher [private] |
boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64MultiArray> > SR06::extra_analog_inputs_publisher [protected] |
std::vector<boost::shared_ptr<rt_pub_int16_t> > SR06::realtime_pub_ [protected] |
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] |
unsigned int SR06::zero_buffer_read [private] |