EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
EthercatLifeCycleNode::EthercatLifeCycle Class Reference

#include <ecat_lifecycle.hpp>

Inheritance diagram for EthercatLifeCycleNode::EthercatLifeCycle:
[legend]
Collaboration diagram for EthercatLifeCycleNode::EthercatLifeCycle:
[legend]

Public Member Functions

 EthercatLifeCycle ()
 
 ~EthercatLifeCycle ()
 

Private Member Functions

node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure (const State &)
 Ethercat lifecycle node configuration function, node will start with this function For more information about Lifecyclenode and it's interfaces check below link : https://design.ros2.org/articles/node_lifecycle.html. More...
 
node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate (const State &)
 Activates Ethercat lifecycle node and starts real-time Ethercat communication. All publishing is done in real-time loop in this active state. More...
 
node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate (const State &)
 Deactivates Ethercat lifecycle node, turns of real-time communication. More...
 
node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup (const State &)
 Cleans up all variables and datas assigned by Ethercat lifecycle node. More...
 
node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown (const State &)
 Shuts down EtherCAT lifecycle node, releases Ethercat master. More...
 
node_interfaces::LifecycleNodeInterface::CallbackReturn on_error (const State &)
 There isn't any error recovery functionality for this node, just resets nodes. Reconfiguration is needed for restarting communication. More...
 
void HandleControlNodeCallbacks (const sensor_msgs::msg::Joy::SharedPtr msg)
 This function handles callbacks from control node. It will update received values from controller node. More...
 
int SetComThreadPriorities ()
 Sets Ethercat communication thread's properties After this function called user must call StartEthercatCommunication() function]. More...
 
int InitEthercatCommunication ()
 Encapsulates all configuration steps for the EtherCAT communication with default slaves. And waits for connected slaves to become operational. More...
 
int StartEthercatCommunication ()
 Starts EtherCAT communcation. More...
 
void StartPdoExchange (void *instance)
 Realtime cyclic Pdo exchange function which will constantly read/write values from/to slaves. More...
 
int GetComState ()
 Gets master's communication state. More...
 
void ReadFromSlaves ()
 Reads data from slaves and updates received data structure to be published. More...
 
int PublishAllData ()
 Publishes all data that master received and will be sent. More...
 
int PublishReceivedData ()
 Publishes received data from slaves under the /slave_feedback name. More...
 
void EnableMotors ()
 Enables connected motor drives based on CIA402. More...
 
void WriteToSlavesVelocityMode ()
 Updates data that will be sent to slaves. This updated data will be published as well. More...
 
void WriteToSlavesInPositionMode ()
 Writes target position and control word to motor in profile position mode. More...
 
void UpdateVelocityModeParameters ()
 Acquired data from subscribed controller topic will be assigned as motor speed parameter. More...
 
void UpdateCyclicVelocityModeParameters ()
 Acquired data from subscribed controller topic will be assigned as motor speed parameter. More...
 
void UpdatePositionModeParameters ()
 Acquired data from subscribed controller topic will be assigned as motor target position parameter. More...
 
void UpdateCyclicPositionModeParameters ()
 Acquired data from subscribed controller topic will be assigned as motor cyclic target position parameter in configured interpolation time. More...
 
void UpdateMotorStateVelocityMode ()
 Updates motor control world and motor state in velocity mode based on CIA402. More...
 
void UpdateMotorStatePositionMode ()
 Updates motor control word and motor state in position mode based on CIA402 state machine,. More...
 
void UpdateCyclicTorqueModeParameters ()
 Updates cylic torque mode parameters based on controller inputs. More...
 
void WriteToSlavesInCyclicTorqueMode ()
 Writes target torque and control word in cyclic sync. torque mode. More...
 
void HandleGuiNodeCallbacks (const ecat_msgs::msg::GuiButtonData::SharedPtr gui_sub)
 CKim - This function checks status word and returns state of the motor driver. More...
 
int GetDriveState (const int &statusWord)
 CKim - This function checks status word and returns state of the motor driver. More...
 
int EnableDrivers ()
 CKim - This function checks status word, clears any faults and enables torque of the motor driver. More...
 
int8_t EnableDrivesViaSDO (int index)
 Enables drives supporting CiA402 in specified index. More...
 
int8_t DisableDrivesViaSDO (int index)
 Disables drives supporting CiA402 in specified index. More...
 
int SetConfigurationParameters ()
 Assigns operation mode parameters based on selected operation mode. More...
 
void UpdateControlParameters ()
 Updates control parameters based on selected mode. More...
 

Static Private Member Functions

static void * PassCycylicExchange (void *arg)
 Helper function to enter pthread_create, since pthread's are C function it doesn't accept class member function, to pass class member function this helper function is created. More...
 

Private Attributes

rclcpp::TimerBase::SharedPtr timer_
 
LifecyclePublisher< ecat_msgs::msg::DataReceived >::SharedPtr received_data_publisher_
 This lifecycle publisher will be used to publish received feedback data from slaves. More...
 
LifecyclePublisher< ecat_msgs::msg::DataSent >::SharedPtr sent_data_publisher_
 This lifecycle publisher will be used to publish sent data from master to slaves. More...
 
rclcpp::Subscription< sensor_msgs::msg::Joy >::SharedPtr joystick_subscriber_
 This subscriber will be used to receive data from controller node. More...
 
rclcpp::Subscription< ecat_msgs::msg::GuiButtonData >::SharedPtr gui_subscriber_
 
ecat_msgs::msg::DataReceived received_data_
 
ecat_msgs::msg::DataSent sent_data_
 
std::unique_ptr< EthercatNodeecat_node_
 
pthread_t ethercat_thread_
 pthread create required parameters. More...
 
struct sched_param ethercat_sched_param_ = {}
 
pthread_attr_t ethercat_thread_attr_
 
int32_t err_
 
uint8_t al_state_ = 0
 Application layer of slaves seen by master.(INIT/PREOP/SAFEOP/OP) More...
 
uint32_t motor_state_ [g_kNumberOfServoDrivers]
 
uint32_t command_ = 0x004F
 
Controller controller_
 
ecat_msgs::msg::GuiButtonData gui_buttons_status_
 Values will be sent by controller node and will be assigned to variables below. More...
 
uint8_t gui_node_data_ = 1
 
uint8_t emergency_status_ = 1
 
std::int32_t measurement_time = 0
 
Timing timer_info_
 

Constructor & Destructor Documentation

◆ EthercatLifeCycle()

EthercatLifeCycle::EthercatLifeCycle ( )

◆ ~EthercatLifeCycle()

EthercatLifeCycle::~EthercatLifeCycle ( )

Member Function Documentation

◆ DisableDrivesViaSDO()

int8_t EthercatLifeCycle::DisableDrivesViaSDO ( int  index)
private

Disables drives supporting CiA402 in specified index.

Parameters
indexslave index
Returns
0 if successful, otherwise -1.

◆ EnableDrivers()

int EthercatLifeCycle::EnableDrivers ( )
private

CKim - This function checks status word, clears any faults and enables torque of the motor driver.

◆ EnableDrivesViaSDO()

int8_t EthercatLifeCycle::EnableDrivesViaSDO ( int  index)
private

Enables drives supporting CiA402 in specified index.

Parameters
indexslave index
Returns
0 if successfull, otherwise -1.

◆ EnableMotors()

void EthercatLifeCycle::EnableMotors ( )
private

Enables connected motor drives based on CIA402.

◆ GetComState()

int EthercatLifeCycle::GetComState ( )
private

Gets master's communication state.

See also
ec_al_state_t
Returns
Application layer state for master.

◆ GetDriveState()

int EthercatLifeCycle::GetDriveState ( const int &  statusWord)
private

CKim - This function checks status word and returns state of the motor driver.

◆ HandleControlNodeCallbacks()

void EthercatLifeCycle::HandleControlNodeCallbacks ( const sensor_msgs::msg::Joy::SharedPtr  msg)
private

This function handles callbacks from control node. It will update received values from controller node.

◆ HandleGuiNodeCallbacks()

void EthercatLifeCycle::HandleGuiNodeCallbacks ( const ecat_msgs::msg::GuiButtonData::SharedPtr  gui_sub)
private

CKim - This function checks status word and returns state of the motor driver.

This function will handle values from GUI node. Updates parameters based on GUI node inputs.

◆ InitEthercatCommunication()

int EthercatLifeCycle::InitEthercatCommunication ( )
private

Encapsulates all configuration steps for the EtherCAT communication with default slaves. And waits for connected slaves to become operational.

Returns
0 if succesful otherwise -1.

◆ on_activate()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_activate ( const State &  )
private

Activates Ethercat lifecycle node and starts real-time Ethercat communication. All publishing is done in real-time loop in this active state.

Returns
Success if activation successfull,otherwise FAILURE

◆ on_cleanup()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_cleanup ( const State &  )
private

Cleans up all variables and datas assigned by Ethercat lifecycle node.

Returns
Success if cleanup successfull,otherwise FAILURE

◆ on_configure()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_configure ( const State &  )
private

Ethercat lifecycle node configuration function, node will start with this function For more information about Lifecyclenode and it's interfaces check below link : https://design.ros2.org/articles/node_lifecycle.html.

See also
node_interfaces::LifecycleNodeInterface::CallbackReturn
Returns
Success if configuration successfull,otherwise FAILURE

◆ on_deactivate()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_deactivate ( const State &  )
private

Deactivates Ethercat lifecycle node, turns of real-time communication.

Returns
Success if deactivation successfull,otherwise FAILURE

◆ on_error()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_error ( const State &  )
private

There isn't any error recovery functionality for this node, just resets nodes. Reconfiguration is needed for restarting communication.

Returns
Success

◆ on_shutdown()

node_interfaces::LifecycleNodeInterface::CallbackReturn EthercatLifeCycle::on_shutdown ( const State &  )
private

Shuts down EtherCAT lifecycle node, releases Ethercat master.

Returns
Success if shut down successfull,otherwise FAILURE

◆ PassCycylicExchange()

void * EthercatLifeCycle::PassCycylicExchange ( void *  arg)
staticprivate

Helper function to enter pthread_create, since pthread's are C function it doesn't accept class member function, to pass class member function this helper function is created.

Parameters
argPointer to current class instance.
Returns
void*

◆ PublishAllData()

int EthercatLifeCycle::PublishAllData ( )
private

Publishes all data that master received and will be sent.

Returns
0 if successfull otherwise -1.

◆ PublishReceivedData()

int EthercatLifeCycle::PublishReceivedData ( )
private

Publishes received data from slaves under the /slave_feedback name.

Returns
0 if successfull, otherwise -1.

◆ ReadFromSlaves()

void EthercatLifeCycle::ReadFromSlaves ( )
private

Reads data from slaves and updates received data structure to be published.

◆ SetComThreadPriorities()

int EthercatLifeCycle::SetComThreadPriorities ( )
private

Sets Ethercat communication thread's properties After this function called user must call StartEthercatCommunication() function].

Returns
0 if successfull, otherwise -1.

◆ SetConfigurationParameters()

int EthercatLifeCycle::SetConfigurationParameters ( )
private

Assigns operation mode parameters based on selected operation mode.

Note
That if you want to change the parameters just change it by modifying this function.
By default operation mode is selected as profile velocity mode.
Returns
0 if succesful, otherwise -1.

◆ StartEthercatCommunication()

int EthercatLifeCycle::StartEthercatCommunication ( )
private

Starts EtherCAT communcation.

Returns
0 if successfull, otherwise -1.

◆ StartPdoExchange()

void EthercatLifeCycle::StartPdoExchange ( void *  instance)
private

Realtime cyclic Pdo exchange function which will constantly read/write values from/to slaves.

Parameters
argUsed during pthread_create function to pass variables to realtime task.
Returns
NULL

◆ UpdateControlParameters()

void EthercatLifeCycle::UpdateControlParameters ( )
private

Updates control parameters based on selected mode.

◆ UpdateCyclicPositionModeParameters()

void EthercatLifeCycle::UpdateCyclicPositionModeParameters ( )
private

Acquired data from subscribed controller topic will be assigned as motor cyclic target position parameter in configured interpolation time.

WRITE YOUR CUSTOM CONTROL ALGORITHM, VARIABLES DECLARATAION HERE, LIKE IN EXAMPLE BELOW.

◆ UpdateCyclicTorqueModeParameters()

void EthercatLifeCycle::UpdateCyclicTorqueModeParameters ( )
private

Updates cylic torque mode parameters based on controller inputs.

◆ UpdateCyclicVelocityModeParameters()

void EthercatLifeCycle::UpdateCyclicVelocityModeParameters ( )
private

Acquired data from subscribed controller topic will be assigned as motor speed parameter.

WRITE YOUR CUSTOM CONTROL ALGORITHM, VARIABLES DECLARATAION HERE, LIKE IN EXAMPLE BELOW.

◆ UpdateMotorStatePositionMode()

void EthercatLifeCycle::UpdateMotorStatePositionMode ( )
private

Updates motor control word and motor state in position mode based on CIA402 state machine,.

◆ UpdateMotorStateVelocityMode()

void EthercatLifeCycle::UpdateMotorStateVelocityMode ( )
private

Updates motor control world and motor state in velocity mode based on CIA402.

◆ UpdatePositionModeParameters()

void EthercatLifeCycle::UpdatePositionModeParameters ( )
private

Acquired data from subscribed controller topic will be assigned as motor target position parameter.

WRITE YOUR CUSTOM CONTROL ALGORITHM, VARIABLES DECLARATAION HERE, LIKE IN EXAMPLE BELOW. KEEP IN MIND THAT YOU WILL HAVE TO WAIT FOR THE MOTION TO FINISH IN POSITION MODE, THEREFORE YOU HAVE TO CHECK 10th BIT OF STATUS WORD TO CHECK WHETHER TARGET IS REACHED OR NOT.

◆ UpdateVelocityModeParameters()

void EthercatLifeCycle::UpdateVelocityModeParameters ( )
private

Acquired data from subscribed controller topic will be assigned as motor speed parameter.

WRITE YOUR CUSTOM CONTROL ALGORITHM VARIABLES DECLARATAION HERE

WRITE YOUR CUSTOM CONTROL ALGORITHM HERE IF YOU WANT TO USE VELOCITY MODE

YOU CAN CHECK EXAMPLE CONTROL CODE BELOW.

◆ WriteToSlavesInCyclicTorqueMode()

void EthercatLifeCycle::WriteToSlavesInCyclicTorqueMode ( )
private

Writes target torque and control word in cyclic sync. torque mode.

◆ WriteToSlavesInPositionMode()

void EthercatLifeCycle::WriteToSlavesInPositionMode ( )
private

Writes target position and control word to motor in profile position mode.

◆ WriteToSlavesVelocityMode()

void EthercatLifeCycle::WriteToSlavesVelocityMode ( )
private

Updates data that will be sent to slaves. This updated data will be published as well.

Member Data Documentation

◆ al_state_

uint8_t EthercatLifeCycleNode::EthercatLifeCycle::al_state_ = 0
private

Application layer of slaves seen by master.(INIT/PREOP/SAFEOP/OP)

◆ command_

uint32_t EthercatLifeCycleNode::EthercatLifeCycle::command_ = 0x004F
private

◆ controller_

Controller EthercatLifeCycleNode::EthercatLifeCycle::controller_
private

◆ ecat_node_

std::unique_ptr<EthercatNode> EthercatLifeCycleNode::EthercatLifeCycle::ecat_node_
private

◆ emergency_status_

uint8_t EthercatLifeCycleNode::EthercatLifeCycle::emergency_status_ = 1
private

◆ err_

int32_t EthercatLifeCycleNode::EthercatLifeCycle::err_
private

◆ ethercat_sched_param_

struct sched_param EthercatLifeCycleNode::EthercatLifeCycle::ethercat_sched_param_ = {}
private

◆ ethercat_thread_

pthread_t EthercatLifeCycleNode::EthercatLifeCycle::ethercat_thread_
private

pthread create required parameters.

◆ ethercat_thread_attr_

pthread_attr_t EthercatLifeCycleNode::EthercatLifeCycle::ethercat_thread_attr_
private

◆ gui_buttons_status_

ecat_msgs::msg::GuiButtonData EthercatLifeCycleNode::EthercatLifeCycle::gui_buttons_status_
private

Values will be sent by controller node and will be assigned to variables below.

◆ gui_node_data_

uint8_t EthercatLifeCycleNode::EthercatLifeCycle::gui_node_data_ = 1
private

◆ gui_subscriber_

rclcpp::Subscription<ecat_msgs::msg::GuiButtonData>::SharedPtr EthercatLifeCycleNode::EthercatLifeCycle::gui_subscriber_
private

◆ joystick_subscriber_

rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr EthercatLifeCycleNode::EthercatLifeCycle::joystick_subscriber_
private

This subscriber will be used to receive data from controller node.

◆ measurement_time

std::int32_t EthercatLifeCycleNode::EthercatLifeCycle::measurement_time = 0
private

◆ motor_state_

uint32_t EthercatLifeCycleNode::EthercatLifeCycle::motor_state_[g_kNumberOfServoDrivers]
private

◆ received_data_

ecat_msgs::msg::DataReceived EthercatLifeCycleNode::EthercatLifeCycle::received_data_
private

◆ received_data_publisher_

LifecyclePublisher<ecat_msgs::msg::DataReceived>::SharedPtr EthercatLifeCycleNode::EthercatLifeCycle::received_data_publisher_
private

This lifecycle publisher will be used to publish received feedback data from slaves.

◆ sent_data_

ecat_msgs::msg::DataSent EthercatLifeCycleNode::EthercatLifeCycle::sent_data_
private

◆ sent_data_publisher_

LifecyclePublisher<ecat_msgs::msg::DataSent>::SharedPtr EthercatLifeCycleNode::EthercatLifeCycle::sent_data_publisher_
private

This lifecycle publisher will be used to publish sent data from master to slaves.

◆ timer_

rclcpp::TimerBase::SharedPtr EthercatLifeCycleNode::EthercatLifeCycle::timer_
private

◆ timer_info_

Timing EthercatLifeCycleNode::EthercatLifeCycle::timer_info_
private

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