EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
ecat_node.hpp
Go to the documentation of this file.
1/******************************************************************************
2 *
3 * $Id$
4 *
5 * Copyright (C) 2021 Veysi ADIN, UST KIST
6 *
7 * This file is part of the Wrapped IgH EtherCAT master userspace program
8 * for control applications.
9 *
10 * The Wrapped IgH EtherCAT master userspace program for control application
11 * in userspace is free software; you canredistribute it and/or modify it
12 * under the terms of the GNU General Public License as published by the
13 * Free Software Foundation; version 2 of the License.
14 *
15 * The Wrapped IgH EtherCAT master userspace program for control application
16 * is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY;
17 * without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
18 * PURPOSE.
19 * See the GNU General Public License for more details.
20 *
21 * You should have received a copy of the GNU General Public License
22 * along with the Wrapped IgH EtherCAT master userspace program for control application.
23 * If not, see <http://www.gnu.org/licenses/>.
24 *
25 * ---
26 *
27 * The license mentioned above concerns the source code only. Using the
28 * EtherCAT technology and brand is only permitted in compliance with the
29 * industrial property and similar rights of Beckhoff Automation GmbH.
30 *
31 * Contact information: veysi.adin@kist.re.kr
32 *****************************************************************************/
33/******************************************************************************
34 * \file ecat_node.hpp
35 * \brief IgH EtherCAT library functionality wrapper class header file.
36 *
37 * This header file contains blueprint of EthercatNode class which will be
38 * responsible for encapsulating IgH EtherCAT library's functionality.
39 *******************************************************************************/
40#pragma once
41/******************************************************************************/
42#include "ecat_globals.hpp"
43/******************************************************************************/
44// Forward declaration of EthercatSlave class.
45class EthercatSlave ;
46#include "ecat_slave.hpp"
47/******************************************************************************/
48
50{
56{
57 public:
67 int ConfigureMaster();
74 void SetCustomSlave(EthercatSlave c_slave, int position);
79 int ConfigureSlaves();
87 int SetProfilePositionParameters(ProfilePosParam& P , int position);
125
140
149
156
157
165 int MapDefaultPdos();
173 int MapCustomPdos(EthercatSlave c_slave, int position);
178 void ConfigDcSyncDefault();
188 void ConfigDcSync(uint16_t assign_activate, int position);
200 int CheckMasterState();
213 int ActivateMaster();
219 int RegisterDomain();
228
234 int OpenEthercatMaster();
246
254 void ReleaseMaster();
266 uint8_t SdoRead(SDO_data &pack);
273 uint8_t SdoWrite(SDO_data &pack);
274 private:
276 int fd;
277
278};
279}
Class for encapsulating IgH EtherCAT library functionality.
Definition: ecat_node.hpp:56
EthercatNode()
Definition: ecat_node.cpp:15
~EthercatNode()
Definition: ecat_node.cpp:20
int SetProfileVelocityParameters(ProfileVelocityParam &P, int position)
Set mode to ProfileVelocityMode with specified parameters for servo drive in specified position.
Definition: ecat_node.cpp:323
int GetNumberOfConnectedSlaves()
Get the number Of physically connected slaves to the bus.And checks if specified NUM_OF_SLAVES is cor...
Definition: ecat_node.cpp:701
int MapDefaultPdos()
Maps default PDOs for our application.
Definition: ecat_node.cpp:65
int WaitForOperationalMode()
Puts all slave to operational mode. User must call this before entering real-time operation....
Definition: ecat_node.cpp:589
int SetCyclicSyncTorqueModeParameters(CSTorqueModeParam &P, int position)
Set the Cyclic Sync Torque Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:547
int SetCyclicSyncPositionModeParameters(CSPositionModeParam &P, int position)
Set the Cyclic Sync Position Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:395
int fd
File descriptor to open and wake master from CLI.
Definition: ecat_node.hpp:276
int OpenEthercatMaster()
Opens EtherCAT master via command line tool if it's not already on.
Definition: ecat_node.cpp:728
int ConfigureMaster()
Requests master instance and creates a domain for a master.
Definition: ecat_node.cpp:25
int ConfigureSlaves()
Obtains slave configuration for all slaves w.r.t master.
Definition: ecat_node.cpp:49
void ConfigDcSyncDefault()
Configures DC sync for our default configuration.
Definition: ecat_node.cpp:209
void ConfigDcSync(uint16_t assign_activate, int position)
Configures DC synchronization for specified slave position.
Definition: ecat_node.cpp:648
int RegisterDomain()
Registers domain for each slave. This method has to be called after ecrt_master_activate() to get the...
Definition: ecat_node.cpp:228
int MapCustomPdos(EthercatSlave c_slave, int position)
Map Custom PDO based on your PDO mappings.
Definition: ecat_node.cpp:632
int SetProfilePositionParametersAll(ProfilePosParam &P)
Set the mode to ProfilePositionMode with specified Parameters for all servo drives on the bus.
Definition: ecat_node.cpp:281
int SetCyclicSyncVelocityModeParameters(CSVelocityModeParam &P, int position)
Set the Cyclic Sync Velocity Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:477
void CheckSlaveConfigurationState()
This function will check slave's application layer states. (INIT/PREOP/SAFEOP/OP)
Definition: ecat_node.cpp:653
int SetProfilePositionParameters(ProfilePosParam &P, int position)
Set mode to ProfilePositionMode with specified parameters for drive in specified position.
Definition: ecat_node.cpp:241
uint8_t SdoWrite(SDO_data &pack)
Writes data to specied slave's index and subindex via SDO.
Definition: ecat_node.cpp:775
uint8_t SdoRead(SDO_data &pack)
Reads data from specified slave index and subindex via SDO. Writes data to pack.data.
Definition: ecat_node.cpp:765
int ActivateMaster()
Activates master, after this function call realtime operation can start.
Definition: ecat_node.cpp:219
int SetCyclicSyncPositionModeParametersAll(CSPositionModeParam &P)
Sets the Cyclic Synchronous Position Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:435
int SetCyclicSyncTorqueModeParametersAll(CSTorqueModeParam &P)
Sets the Cyclic Synchronous Torque Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:567
void GetAllSlaveInformation()
Get the information of physically connected slaves to the master. This function will return connected...
Definition: ecat_node.cpp:42
int SetProfileVelocityParametersAll(ProfileVelocityParam &P)
Set mode to ProfileVelocityMode with specified parameters for all servo drives on the bus.
Definition: ecat_node.cpp:358
void ReleaseMaster()
Deactivates and releases master shouldn't be called in real-time.
Definition: ecat_node.cpp:722
int ShutDownEthercatMaster()
Shutdowns EtherCAT master via command line tool if it's not already off.
Definition: ecat_node.cpp:746
void SetCustomSlave(EthercatSlave c_slave, int position)
Passes your defined slave to EthercatNode class.
Definition: ecat_node.cpp:627
int SetCyclicSyncVelocityModeParametersAll(CSVelocityModeParam &P)
Sets the Cyclic Synchronous Velocity Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:511
EthercatSlave slaves_[NUM_OF_SLAVES]
Slave instances.
Definition: ecat_node.hpp:61
int CheckMasterState()
This function will check master's state, in terms of number of responding slaves and their applicatio...
Definition: ecat_node.cpp:662
void CheckMasterDomainState()
Reads the state of a domain. Stores the domain state in the given state structure....
Definition: ecat_node.cpp:687
void DeactivateCommunication()
Deactivates slaves and can be called in real-time.
Definition: ecat_node.cpp:716
Contains EtherCAT slave parameters for configuration.
Definition: ecat_slave.hpp:50
#define NUM_OF_SLAVES
Total number of connected slave to the bus.
Definition: ecat_globals.hpp:79
Definition: ecat_node.hpp:50
Struct contains configuration parameters for cyclic sync. position mode.
Definition: ecat_globals.hpp:396
Struct contains configuration parameters for cyclic sync. torque mode.
Definition: ecat_globals.hpp:443
Struct contains configuration parameters for cyclic sync. velocity mode.
Definition: ecat_globals.hpp:430
Parameters that should be specified in position mode.
Definition: ecat_globals.hpp:378
Profile velocity mode configuration parameters.
Definition: ecat_globals.hpp:475
SDO_data Structure holding all data needed to send an SDO object.
Definition: ecat_globals.hpp:205