![]() |
EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
|
#include <ecat_lifecycle.hpp>
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< EthercatNode > | ecat_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_ |
EthercatLifeCycle::EthercatLifeCycle | ( | ) |
EthercatLifeCycle::~EthercatLifeCycle | ( | ) |
|
private |
Disables drives supporting CiA402 in specified index.
index | slave index |
|
private |
CKim - This function checks status word, clears any faults and enables torque of the motor driver.
|
private |
Enables drives supporting CiA402 in specified index.
index | slave index |
|
private |
Enables connected motor drives based on CIA402.
|
private |
Gets master's communication state.
|
private |
CKim - This function checks status word and returns state of the motor driver.
|
private |
This function handles callbacks from control node. It will update received values from controller node.
|
private |
|
private |
Encapsulates all configuration steps for the EtherCAT communication with default slaves. And waits for connected slaves to become operational.
|
private |
Activates Ethercat lifecycle node and starts real-time Ethercat communication. All publishing is done in real-time loop in this active state.
|
private |
Cleans up all variables and datas assigned by Ethercat lifecycle node.
|
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.
|
private |
Deactivates Ethercat lifecycle node, turns of real-time communication.
|
private |
There isn't any error recovery functionality for this node, just resets nodes. Reconfiguration is needed for restarting communication.
|
private |
Shuts down EtherCAT lifecycle node, releases Ethercat master.
|
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.
arg | Pointer to current class instance. |
|
private |
Publishes all data that master received and will be sent.
|
private |
Publishes received data from slaves under the /slave_feedback name.
|
private |
Reads data from slaves and updates received data structure to be published.
|
private |
Sets Ethercat communication thread's properties After this function called user must call StartEthercatCommunication() function].
|
private |
Assigns operation mode parameters based on selected operation mode.
|
private |
Starts EtherCAT communcation.
|
private |
Realtime cyclic Pdo exchange function which will constantly read/write values from/to slaves.
arg | Used during pthread_create function to pass variables to realtime task. |
|
private |
Updates control parameters based on selected mode.
|
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.
|
private |
Updates cylic torque mode parameters based on controller inputs.
|
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.
|
private |
Updates motor control word and motor state in position mode based on CIA402 state machine,.
|
private |
Updates motor control world and motor state in velocity mode based on CIA402.
|
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.
|
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.
|
private |
Writes target torque and control word in cyclic sync. torque mode.
|
private |
Writes target position and control word to motor in profile position mode.
|
private |
Updates data that will be sent to slaves. This updated data will be published as well.
|
private |
Application layer of slaves seen by master.(INIT/PREOP/SAFEOP/OP)
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
pthread create required parameters.
|
private |
|
private |
Values will be sent by controller node and will be assigned to variables below.
|
private |
|
private |
|
private |
This subscriber will be used to receive data from controller node.
|
private |
|
private |
|
private |
|
private |
This lifecycle publisher will be used to publish received feedback data from slaves.
|
private |
|
private |
This lifecycle publisher will be used to publish sent data from master to slaves.
|
private |
|
private |