47#include <rclcpp/rclcpp.hpp>
48#include "sensor_msgs/msg/joy.hpp"
196 void ConfigDcSync(uint16_t assign_activate,
int position);
283 void WriteSDO(ec_sdo_request_t *req, int32_t data,
int size);
289 uint16_t
ReadSDO(ec_sdo_request_t *req,uint16_t &status_word);
Definition: ecat_node.hpp:53
EthercatNode()
Definition: ecat_node.cpp:15
~EthercatNode()
Definition: ecat_node.cpp:20
int32_t ReadActualVelocityViaSDO(int index)
Reads actual velocity value from slave in specified index via SDO.
Definition: ecat_node.cpp:910
int16_t WriteTargetPositionViaSDO(int index, int32_t target_pos)
Writes target position value via SDO to slave in specified index.
Definition: ecat_node.cpp:960
int SetProfileVelocityParameters(ProfileVelocityParam &P, int position)
Set mode to ProfileVelocityMode with specified parameters for servo drive on that position.
Definition: ecat_node.cpp:360
int8_t SdoRead(SDO_data &pack)
This function reads data from specified index and subindex via SDO, returned data will be stored in p...
Definition: ecat_node.cpp:826
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:745
int MapDefaultPdos()
Maps default PDOs for the application.
Definition: ecat_node.cpp:67
int WaitForOperationalMode()
Puts all slave to operational mode. User must call this before entering real-time operation....
Definition: ecat_node.cpp:633
int SetCyclicSyncTorqueModeParameters(CSTorqueModeParam &P, int position)
Set the Cyclic Sync Torque Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:549
int SetCyclicSyncPositionModeParameters(CSPositionModeParam &P, int position)
Set the Cyclic Sync Position Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:432
int fd
File descriptor to open and wake master from CLI.
Definition: ecat_node.hpp:401
int OpenEthercatMaster()
Opens EtherCAT master via command line tool if it's not already on.
Definition: ecat_node.cpp:772
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:51
void ConfigDcSyncDefault()
Configures DC sync for our default configuration.
Definition: ecat_node.cpp:246
void ConfigDcSync(uint16_t assign_activate, int position)
Configures DC synchronization for specified slave position.
Definition: ecat_node.cpp:692
int RegisterDomain()
Registers domain for each slave. This method has to be called after ecrt_master_activate() to get the...
Definition: ecat_node.cpp:265
int16_t EnableDrivesViaSDO(int index)
Enable CiA402 supported motor drives in specified index via SDO.
int MapCustomPdos(EthercatSlave c_slave, int position)
Map Custom PDO based on your PDO mappings.
Definition: ecat_node.cpp:676
int SetProfilePositionParametersAll(ProfilePosParam &P)
Set the mode to ProfilePositionMode with specified Parameters for all servo drives on the bus.
Definition: ecat_node.cpp:318
int SetCyclicSyncVelocityModeParameters(CSVelocityModeParam &P, int position)
Set the Cyclic Sync Velocity Mode Parameters for slave in specified physical position w....
Definition: ecat_node.cpp:514
uint8_t ReadOpModeViaSDO(int index)
Reads current operational mode from slave in specified index via SDO.
Definition: ecat_node.cpp:879
int16_t WriteOpModeViaSDO(int index, uint8_t op_mode)
Definition: ecat_node.cpp:895
void CheckSlaveConfigurationState()
This function will check slave's application layer states. (INIT/PREOP/SAFEOP/OP)
Definition: ecat_node.cpp:697
int SetProfilePositionParameters(ProfilePosParam &P, int position)
Set mode to ProfilePositionMode with specified parameters for servo drive on that position.
Definition: ecat_node.cpp:278
int RestartEthercatMaster()
Restarts Ethercat master via command line tool.
Definition: ecat_node.cpp:811
int16_t WriteTargetTorqueViaSDO(int index, uint16_t target_tor)
Writes target torque value to slave in specified index via SDO.
Definition: ecat_node.cpp:999
uint16_t ReadStatusWordViaSDO(int index)
Get the Status Word from CiA402 slaves in specified index via SDO communication.
Definition: ecat_node.cpp:848
int ActivateMaster()
Activates master, after this function call realtime operation can start.
Definition: ecat_node.cpp:256
int8_t SdoWrite(SDO_data &pack)
This function writes data to specified index and subindex via SDO.
Definition: ecat_node.cpp:837
int16_t ReadActualTorqueViaSDO(int index)
Read actual torque value from slave in specified index via SDO.
Definition: ecat_node.cpp:983
int SetCyclicSyncPositionModeParametersAll(CSPositionModeParam &P)
Sets the Cyclic Synchronous Position Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:472
int SetCyclicSyncTorqueModeParametersAll(CSTorqueModeParam &P)
Sets the Cyclic Synchronous Torque Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:611
int32_t ReadActualPositionViaSDO(int index)
Read actual position from slave in specified index via SDO.
Definition: ecat_node.cpp:944
void GetAllSlaveInformation()
Get the information of physically connected slaves to the master. This function will return connected...
Definition: ecat_node.cpp:44
int16_t DisableDrivesViaSDO(int index)
Disable CiA402 supported motor drives in specified index via SDO.
int SetProfileVelocityParametersAll(ProfileVelocityParam &P)
Set mode to ProfileVelocityMode with specified parameters for all servo drives on the bus.
Definition: ecat_node.cpp:395
int MapDefaultSdos()
Maps default SDOs which can be found.
Definition: ecat_node.cpp:1017
void ReleaseMaster()
Deactivates and releases master shouldn't be called in real-time.
Definition: ecat_node.cpp:767
void WriteSDO(ec_sdo_request_t *req, int32_t data, int size)
Writes SDO in real-time context.
Definition: ecat_node.cpp:1083
std::vector< SdoRequest > request_sdos_
Definition: ecat_node.hpp:58
int ShutDownEthercatMaster()
Shutdowns EtherCAT master via command line tool if it's not already off.
Definition: ecat_node.cpp:792
void SetCustomSlave(EthercatSlave c_slave, int position)
Passes your defined slave to EthercatNode class.
Definition: ecat_node.cpp:671
int SetCyclicSyncVelocityModeParametersAll(CSVelocityModeParam &P)
Sets the Cyclic Synchronous Velocity Mode Parameters for all connected motor driver slaves.
Definition: ecat_node.cpp:570
EthercatSlave slaves_[NUM_OF_SLAVES]
Definition: ecat_node.hpp:57
void DefineDefaultSlaves()
Defines default connected slaves based on number of slaves. Specifies its position,...
uint16_t ReadSDO(ec_sdo_request_t *req, uint16_t &status_word)
Reads SDO in real-time context by creating read request.
Definition: ecat_node.cpp:1109
int16_t WriteTargetVelocityViaSDO(int index, int32_t target_vel)
Writes target velocity value via SDO to slave in specified index.
Definition: ecat_node.cpp:926
int16_t WriteControlWordViaSDO(int index, uint16_t control_word)
Writes control word to slave in specified index via SDO.
Definition: ecat_node.cpp:864
int CheckMasterState()
This function will check master's state, in terms of number of responding slaves and their applicatio...
Definition: ecat_node.cpp:706
void CheckMasterDomainState()
Reads the state of a domain. Stores the domain state in the given state structure....
Definition: ecat_node.cpp:731
void DeactivateCommunication()
Deactivates master, and it is used to stop cyclic PDO exchange.
Definition: ecat_node.cpp:760
Definition: ecat_slave.hpp:50
#define NUM_OF_SLAVES
Definition: ecat_globals.hpp:50
ROS2 Headers.
Definition: ecat_node.hpp:51
Struct contains configuration parameters for cyclic sync. position mode.
Definition: ecat_definitions.hpp:339
Struct contains configuration parameters for cyclic sync. torque mode.
Definition: ecat_definitions.hpp:385
Struct contains configuration parameters for cyclic sync. velocity mode.
Definition: ecat_definitions.hpp:372
Parameters that should be specified in position mode.
Definition: ecat_definitions.hpp:322
Parameters that should be specified in velocity mode.
Definition: ecat_definitions.hpp:418
CKim - SDO_data Structure holding all data needed to send/receive an SDO object.
Definition: ecat_definitions.hpp:286