Files / Classes

Header Files

EtherCAT Communicator header file

Header file for the EthercatCommunicator class.

Defines

DC_FILTER_CNT
SYNC_REF_TO_MASTER
FIFO_SCHEDULING
class EthercatCommunicator
#include <ethercat_communicator.h>

The Ethercat Communicator class.

Basic class for implementing realtime pure communication purposes, from our application to the Ethercat slaves, via IgH Master module. The class uses the POSIX API for gaining realtime attributes.

Public Functions

void init(ros::NodeHandle &n)

Initializes the main thread.

Mostly makes ready the attributes of the realtime thread, before running.

Parameters
  • n: The ROS Node Handle

void start()

Starts the main thread.

The function that actually starts the realtime thread. The realtime attributes have been set from init. Implements the basic realtime communication (Tx/Rx) with the EtherCAT slaves. Doesn’t change the output PDOs. Basic state machine:

  • Receive the new PDOs in domain1_pd from the IgH Master Module (and therefore from the EtherCAT slaves)
  • Move to the domain_pd the output data of process_data_buf, safely
  • Publish the “raw” data (not linked to EtherCAT variables) in PDOs received from the domain1_pd, to the /ethercat_data_raw topic
  • Synchronize the DC of every slave (every count’nth cycle)
  • Send the new PDOs from domain1_pd to the IgH Master Module (and then to EtherCAT slaves)
    See
    void init(ros::NodeHandle &n)

void stop()

Stops the main thread.

This function stops the execution of the realtime thread. The mechanism for stopping it, is provided by the POSIX API. Search for pthread_testcancel() and other related functions.

Public Static Functions

static bool has_running_thread()

A getter for knowing if there is a running thread.

It’s used from the EthercatCommd service, to know if a user stops/starts an already stopped/started EthercatCommunicator.

Private Members

pthread_attr_t current_thattr_
struct sched_param sched_param_

Private Static Functions

void *run(void *arg)
void cleanup_handler(void *arg)
static void copy_data_to_domain_buf()
void publish_raw_data()
void sync_distributed_clocks(void)

Synchronise the distributed clocks

void update_master_clock(void)

Update the master time based on ref slaves time diff

called after the ethercat frame is sent to avoid time jitter in sync_distributed_clocks()

uint64_t system_time_ns(void)

Get the time in ns for the current cpu, adjusted by system_time_base_.

The time in ns.

Attention
Rather than calling rt_get_time_ns() directly, all application time calls should use this method instead.

Private Static Attributes

int cleanup_pop_arg_ = 0
pthread_t communicator_thread_ = {}
ros::Publisher pdo_raw_pub_
bool running_thread_ = false
uint64_t dc_start_time_ns_ = 0LL
uint64_t dc_time_ns_ = 0
int64_t system_time_base_ = 0LL

Input Process Data Objects publisher header file

Header file for the PDOInPublisher class.

class PDOInPublisher
#include <pdo_in_publisher.h>

The Ethercat Input Data Handler class.

Used for trasforming the “raw” indexed data from the /pdo_raw topic, sent by the Ethercat Communicator, to values of variables, and stream them to the /pdo_in_slave_{slave_id} topic.

Public Functions

void init(ros::NodeHandle &n)

Initialization Method.

Used for initializing the PDOInPublisher object. It’s basically the main method in the class, which initializes the listener to the afore mentioned topic.

Parameters
  • n: The ROS Node Handle

void pdo_raw_callback(const ether_ros::PDORaw::ConstPtr &pdo_raw)

Raw Data Callback.

This method, is called when there are data in the /pdo_raw topic. Should the EtherCAT application change, this callback must change also. Implements the basic functionality of the class, to transform the “raw” data into variable values and pipe them into another topic.

Parameters
  • pdo_raw: A copy of the actual data sent to the topic /pdo_raw.

Private Members

ros::Subscriber pdo_raw_sub_
ros::Publisher *pdo_in_pub_

Output Process Data Objects publisher header file

Header file for the PDOOutPublisher class.

class PDOOutPublisher
#include <pdo_out_publisher.h>

The Process Data Objects Publisher class.

Used for trasforming the “raw” indexed data from the /pdo_raw topic, sent by the Ethercat Communicator, to values of variables, and stream them to the /pdo_out topic.

Used for streaming the pdo_out data inside the process_data_buffer to the /pdo_out_timer topic at a certain rate. It’s been created for logging and debugging reasons.

Public Functions

void init(ros::NodeHandle &n)

Initialization Method.

Used for initializing the PDOOutPublisher object. It’s basically the main method in the class, which initializes the listener to the afore mentioned topic.

Parameters
  • n: The ROS Node Handle

void pdo_raw_callback(const ether_ros::PDORaw::ConstPtr &pdo_raw)

Process Data Objects Callback.

This method, is called when there are data in the /pdo_raw topic. Should the EtherCAT application change, this callback must change also. Implements the basic functionality of the class, to transform the “raw” data into variable values and pipe them into another topic.

Parameters
  • pdo_raw: A copy of the actual data sent to the topic /pdo_raw.

Private Members

ros::Subscriber pdo_raw_sub_
ros::Publisher pdo_out_pub_

EtherCAT Slave header file

Header file for the EthercatSlave class.

class EthercatSlave
#include <ethercat_slave.h>

The Ethercat Slave class.

Used for having all the ethercat slave related variables, fetched from the correspondent yaml file, in a single entity.

Public Functions

void init(std::string slave, ros::NodeHandle &n)

Initialization Method.

Used for initializing the EthercatSlave entity. It’s basically the main method in the class.

int get_pdo_out()

Getter Method.

Used for getting the number of bytes of the output PDO of the single slave.

int get_pdo_in()

Getter Method.

Used for getting the number of bytes of the input PDO of the single slave.

ec_slave_config_t *get_slave_config()

Private Members

int vendor_id_
std::string slave_id_
int product_code_
int assign_activate_
int position_
int alias_
int input_port_
int output_port_
ec_slave_config_t *ethercat_slave_
int pdo_in_
int pdo_out_
int32_t sync0_shift_

Main header file

Main header file.

Services header file

Services header file.

Includes:

  • EtherCAT Communicator Daemon
  • Services for modifying output PDOs

Functions

bool ethercat_communicatord(ether_ros::EthercatCommd::Request &req, ether_ros::EthercatCommd::Response &res)

ROS Service Callback.

Controls the Ethercat Communicator. The basic functionality is:

  • Start
  • Stop
  • Restart (Remember that a Service Callback must always return a boolean.)

bool start_ethercat_communicator()

Helper function for the ethercat_communicatord callback.

Used from the callback in order to actualy send the start command to the Ethercat Communicator.

bool stop_ethercat_communicator()

Helper function for the ethercat_communicatord callback.

Used from the callback in order to actualy send the stop command to the Ethercat Communicator.

Utilities header file

Utilities header file.

Includes:

  • Functions for processing EtherCAT PDOs
  • Function for insisting write to file
  • Function for safe ascii to integer conversion
  • Function for adding two timespec structs
  • Functions for checking domain and master states

Deadline Scheduler header file

Deadline scheduler header file.

Should be added to the project in order the SCHED_DEADLINE option could be used. I’m not the author of the header file, nor do I claim any copyrights for it. This file is distributed under the GPLv2 licence. See the licence above to get an idea.

Defines

SCHED_DEADLINE

Functions

int sched_setattr(pid_t pid, const struct sched_attr *attr, unsigned int flags)
int sched_getattr(pid_t pid, struct sched_attr *attr, unsigned int size, unsigned int flags)
struct sched_attr
#include <deadline_scheduler.h>

Public Members

__u32 size
__u32 sched_policy
__u64 sched_flags
__s32 sched_nice
__u32 sched_priority
__u64 sched_runtime
__u64 sched_deadline
__u64 sched_period

Source Files

EtherCAT Communicator source file

Implementation of EthercatCommunicator class.

Used for real-time communication with the EtherCAT slaves, via the IgH Master module. The new PD are sent to the /ethercat_data_raw topic.

Input Process Data Objects publisher source file

Implementation of PDOInPublisher class.

Used for publishing the “raw” input data, received from EtherCAT Communicator after transformation into useful, human-readable format, consisted of the EtherCAT variables used by our application. Transforms the indeces to variables.

Output Process Data Objects publisher source file

Implementation of PDOOutPublisher class.

Used for handling the “raw” output data, received from EtherCAT Communicator and transforming them into useful, human-readable format, consisted of the EtherCAT variables used by our application. Transforms the indeces to variables.

Used for streaming the “raw” pdo_out data inside the process_data_buffer to the /pdo_out_timer topic and transforming them into useful, human-readable format, consisted of the EtherCAT output variables used by our application, at a certain rate. It’s been created for logging and debugging reasons.

EtherCAT Slave source file

Implementation of EthercatSlave class.

Used for containing all the useful information of an EtherCAT slave, from the userspace program perspective. Receives all the useful information via the ROS Parameter Server (after they are loaded from ethercat_slaves.yaml).

Main source file

Main source file.

IgH Master EtherCAT module main for realtime communication with EtherCAT slaves. This interface is designed for realtime modules, running in the ROS environment and want to use EtherCAT. There are classes and functions to get the Input and Output PDOs in a realtime context. Before trying to understand the source code of the project, please consider to read and understand the IgH Master Documentation located at: https://www.etherlab.org/download/ethercat/ethercat-1.5.2.pdf. Finally try to understand the API provided in the /opt/etherlab/include/ecrt.h file. The author admits that the C++ language, is not his strong suit. Therefore feel free to refactore the code given with use of the new C++ (11/14/17) helpful tools (unique/shared pointers and other cool stuff).

Changes in version 0.3:

  • Created a frontend UI client in Python, for interacting with the Services API. Features include: Start/Stop function of the EtherCAT Communicator Change the Output PDOs on the run Run script with the aproppriate Service API calls

Changes in version 0.2:

  • Added features and bug fixes including: First realtime characteristics added (debate: FIFO vs DEADLINE scheduling?) Handling of the EtherCAT communicator module: Start/Stop/Restart API
  • Added processing for the /ethercat_data_raw topic and created: Service API for Output PDO handling and topic streaming: /ethercat_output_data Service API for Input PDO handling and topic streaming: /ethercat_data_slave_{slave_id}
  • Added synchronization primitives (spinlocks) for the concurrent threads accessing the EtherCAT buffer.
  • Added more source files, ethercat communicator, ethercat_slave, pdo_in_publisher and pdo_out_publisher. Created external objects to use the appropriate classes and functions.

Version 0.1:

  • Created the first bare communication layer in the ROS environment. Many bugs and deficiencies including: Non realtime characteristics, no API for Output PDO handling and topic streaming, no handling of the EtherCAT communicator module, no Service API for Input PDO topic streaming.
  • One topic streaming: /ethercat_data_raw

Unnamed Group

uint8_t *domain1_pd

Global buffer for the actual communication with the IgH Master Module.

uint8_t *process_data_buf

Global buffer for safe concurrent accesses from the output PDOs services and the EtherCAT Communicator.

See
ethercat_comm

size_t total_process_data

Total number of process data (PD) (bytes).

size_t num_process_data_in

Number of input PD per slave (bytes).

Assumes that the EtherCAT application is the same for every slave.

size_t num_process_data_out

Number of output PD per slave (bytes).

Assumes that the EtherCAT application is the same for every slave.

int log_fd

File descriptor used for logging, provided that LOGGING and one of LOGGING_SAMPLING or LOGGING_NO_SAMPLING is enabled.

Could be deprecated in a next version (see kernelshark).

ec_master_t *master

The main master struct.

Used for communication with the IgH Master Module.

ec_master_state_t master_state

The master state struct.

Used to examine the current state (Links Up/Down, AL states) of the Master.

ec_master_info_t master_info

The master info struct.

Used to know the slaves responding to the Master.

ec_domain_t *domain1

The main domain struct variable.

Used to send and receive the datagrams.

ec_domain_state_t domain1_state

The domain state struct.

Used to examine the current state (Working counter, DL states) of the domain.

See
ethercat_comm

slave_struct *ethercat_slaves

The main slave struct.

Used by our program to contain all the useful info of every slave.

pthread_spinlock_t lock

The shared spinlock.

Used by every thread whick modifies the process_data_buf.

See
process_data_buf

EthercatCommunicator ethercat_comm

The barebone object of our application.

Used for realtime communication (Tx/Rx) with the EtherCAT slaves. Doesn’t change the output PDOs. Basic state machine:

  • Receive the new PDOs in domain1_pd from the IgH Master Module (and then to EtherCAT slaves)
  • Move to the domain_pd the output data of process_data_buf, safely
  • Publish the “raw” data (not linked to EtherCAT variables) in PDOs from the domain1_pd
  • Send the new PDOs from domain1_pd to the IgH Master Module (and then to EtherCAT slaves)

PDOInPublisher pdo_in_publisher
PDOOutPublisher pdo_out_publisher
PDOOutListener pdo_out_listener
PDOOutPublisherTimer pdo_out_publisher_timer
int FREQUENCY
int RUN_TIME
int PERIOD_NS
int main(int argc, char **argv)

Services source file

Implements the services used.

Provides services for:

  • Interacting with the EtherCAT Communicator
  • Changing the EtherCAT output PDOs

Functions

ethercat_communicatord(ether_ros::EthercatCommd::Request &req, ether_ros::EthercatCommd::Response &res)

ROS Service Callback.

Controls the Ethercat Communicator. The basic functionality is:

  • Start
  • Stop
  • Restart (Remember that a Service Callback must always return a boolean.)

start_ethercat_communicator()

Helper function for the ethercat_communicatord callback.

Used from the callback in order to actualy send the start command to the Ethercat Communicator.

stop_ethercat_communicator()

Helper function for the ethercat_communicatord callback.

Used from the callback in order to actualy send the stop command to the Ethercat Communicator.

Utilities source file

A library with useful functions for handling EtherCAT PDOs and other utilities.

namespace utilities

Functions

int safe_atoi(const char *s, int *val)
bool process_input_bit(uint8_t *data_ptr, uint8_t index, uint8_t subindex)
uint8_t process_input_uint8(uint8_t *data_ptr, uint8_t index)
int8_t process_input_int8(uint8_t *data_ptr, uint8_t index)
uint16_t process_input_uint16(uint8_t *data_ptr, uint8_t index)
int16_t process_input_int16(uint8_t *data_ptr, uint8_t index)
uint32_t process_input_uint32(uint8_t *data_ptr, uint8_t index)
int32_t process_input_int32(uint8_t *data_ptr, uint8_t index)
uint64_t process_input_uint64(uint8_t *data_ptr, uint8_t index)
int64_t process_input_int64(uint8_t *data_ptr, uint8_t index)
struct timespec timespec_add(struct timespec time1, struct timespec time2)
void check_domain1_state(void)
void check_master_state(void)
ssize_t insist_write(int fd, const char *buf, size_t count)
std::string &ltrim(std::string &str, const std::string &chars)
std::string &rtrim(std::string &str, const std::string &chars)
std::string &trim(std::string &str, const std::string &chars)
void copy_process_data_buffer_to_buf(uint8_t *buffer)

EtherCAT Keyboard Controller python file

namespace ethercat_keyboard_controller

Variables

string ethercat_keyboard_controller.help_message

= “”“

##################################

## Ethercat Keyboard controller ##

##################################

Changes elliptic trajectory parameters

and controlls the ethercat communicator.

All the terminal commands must beggin with

an exclamation mark “!”.

If you want to find the current application variables,

see the EthercatOutputData.msg.

The current supported commands are:

!start : starts the ethercat communicator

!stop : stops the ethercat communicator

!restart : restarts the ethercat communicator

!variable [slave_id | ‘all’] [variable_name] [value] :

change the value of a variable in the ethercat output data

!run [script_to_run] : run the script specified,

inside the ether_ros/scripts directory

!help : shows this help message

!q : exit the terminal

Type !q to quit

“”“

string ethercat_keyboard_controller.intro_message

= “”“

Welcome to the Ethercat Keyboard Controller!

By Mike Karamousadakis

Contact: mkaramousadakis@zoho.eu

“”“

modify_pdo_pub = rospy.Publisher(‘pdo_listener’, ModifyPDOVariables, queue_size=10)
prompt = ethercat_controller()
intro
class ethercat_controller

Base Ethercat Controller class.

Inherits from the base class Cmd. Serves as a frontend to the C++ code, and specifically to the services implemented.

Public Functions

call_modify_publisher(self self, slave_id slave_id, variable_name variable_name, value value)
modify_output_publisher(self self, slave_id slave_id, index index, subindex subindex, value value, var_type var_type)
ethercat_communicator_client(self self, mode mode)

Frontend client for the ethercat_communicatord service.

Parameters
  • self: The current object.
  • mode: The mode to change to (start/stop/restart).

do_shell(self self, args args)

Main method of ethercat_controller class.

Accepts commnads, decomposes them and acts.

Parameters
  • self: The current object.
  • args: The arguments given from the cmd line.

do_help(self self, line line)

Helper method.

Parameters
  • self: The current object.
  • line: Unrelated argument.Just follow the API

default(self self, line line)

Unrecognized command method.

Parameters
  • self: The current object.
  • line: Unrelated argument.Just follow the API

Public Static Attributes

variables2indeces

= {

“state_machine” : [[0, 0], “bool”],

“initialize_clock”: [[0, 1], “bool”],

“initialize_angles”: [[0, 2], “bool”],

“inverse_kinematics”: [[0, 3], “bool”],

“blue_led”: [[0, 4], “bool”],

“red_led”: [[0, 5], “bool”],

“button_1”: [[0, 6], “bool”],

“button_2”: [[0, 7], “bool”],

“transition_time”: [[1, 0], “int8”],

“desired_x_value”: [[2, 0], “int32”],

“filter_bandwidth”: [[6, 0], “uint16”],

“desired_y_value”: [[8, 0], “int32”],

“kp_100_knee”: [[12, 0], “int16”],

“kd_1000_knee”: [[14, 0], “int16”],

“ki_100_knee”: [[16, 0], “int16”],

“kp_100_hip”: [[18, 0], “int16”],

“kd_1000_hip”: [[20, 0], “int16”],

“ki_100_hip”: [[22, 0], “int16”],

“x_cntr_traj1000”: [[24, 0], “int16”],

“y_cntr_traj1000”: [[26, 0], “int16”],

“a_ellipse100”: [[28, 0], “int16”],

“b_ellipse100”: [[30, 0], “int16”],

“traj_freq100”: [[32, 0], “int16”],

“phase_deg”: [[34, 0], “int16”],

“flatness_param100”: [[36, 0], “int16”]

}

variables2indeces dictionary.

Used for transforming the [index,subindex] -> variable