Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Soem master using with beckhoff driver #662

Closed
ahmetihsankose opened this issue Nov 17, 2022 · 10 comments
Closed

Soem master using with beckhoff driver #662

ahmetihsankose opened this issue Nov 17, 2022 · 10 comments

Comments

@ahmetihsankose
Copy link

ahmetihsankose commented Nov 17, 2022

Hello,
i have a problem with soem master :).
Ethercat states not changing. They stay in preop.
I did the steps in the soem tutorial one by one. I also tried to set of PDO for slaves according to Twincat startup settings. But ec state still stay in pre op.
I read in before issues about of 1c32 and 1c33 indexes to adjust sm. But according to my object dictionary, these indexes are only readable.
There is also ENI file from Twincat Configurator tool is attached.

What can advise me?
Regards!

SOEM (Simple Open EtherCAT Master)
Slaveinfo
Starting slaveinfo
ec_init on eno1 succeeded.
3 slaves found and configured.
Calculated workcounter 1
Not all slaves reached safe operational state.
Slave 1 State=12 StatusCode= 30 : Invalid DC SYNC configuration
Slave 2 State=11 StatusCode= 11 : Invalid requested state change
Slave 3 State=11 StatusCode= 11 : Invalid requested state change

Slave:1
Name:AX8640-0000-0103
Output size: 0bits
Input size: 16bits
State: 18
Delay: 0[ns]
Has DC: 1
DCParentport:0
Activeports:1.1.0.0
Configured address: 1001
Man: 00000002 ID: 21c06012 Rev: 00670000
SM0 A:1000 L: 256 F:00010026 Type:1
SM1 A:1100 L: 256 F:00010022 Type:2
SM2 A:1200 L: 0 F:00000004 Type:3
SM3 A:1900 L: 2 F:00010020 Type:4
FMMU0 Ls:00000000 Ll: 2 Lsb:0 Leb:7 Ps:1900 Psb:0 Ty:01 Act:01
FMMUfunc 0:2 1:3 2:0 3:0
MBX length wr: 128 rd: 128 MBX protocols : 0c
CoE details: 27 FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0

Slave:2
Name:AX8206-0000-0103
Output size: 0bits
Input size: 0bits
State: 17
Delay: 175[ns]
Has DC: 1
DCParentport:1
Activeports:1.1.0.0
Configured address: 1002
Man: 00000002 ID: 200e6012 Rev: 00670000
SM0 A:1000 L: 512 F:00010026 Type:1
SM1 A:1400 L: 512 F:00010022 Type:2
SM2 A:1800 L: 32 F:00010064 Type:3
SM3 A:2a00 L: 32 F:00010020 Type:4
SM4 A:3c00 L: 0 F:00000024 Type:0
SM5 A:4e00 L: 0 F:00000020 Type:0
FMMUfunc 0:1 1:2 2:3 3:5
MBX length wr: 512 rd: 512 MBX protocols : 0d
CoE details: 2f FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0

Slave:3
Name:AX8206-0000-0103
Output size: 0bits
Input size: 0bits
State: 17
Delay: 390[ns]
Has DC: 1
DCParentport:1
Activeports:1.0.0.0
Configured address: 1003
Man: 00000002 ID: 200e6012 Rev: 00670000
SM0 A:1000 L: 512 F:00010026 Type:1
SM1 A:1400 L: 512 F:00010022 Type:2
SM2 A:1800 L: 32 F:00010064 Type:3
SM3 A:2a00 L: 32 F:00010020 Type:4
SM4 A:3c00 L: 0 F:00000024 Type:0
SM5 A:4e00 L: 0 F:00000020 Type:0
FMMUfunc 0:1 1:2 2:3 3:5
MBX length wr: 512 rd: 512 MBX protocols : 0d
CoE details: 2f FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0
End slaveinfo, close socket
End program

3 slaves found and configured.
Calculated workcounter 7
Not all slaves reached safe operational state.
Slave 1 State=12 StatusCode= 30 : Invalid DC SYNC configuration
Slave 2 State=12 StatusCode= 30 : Invalid DC SYNC configuration
Slave 3 State=12 StatusCode= 30 : Invalid DC SYNC configuration

Slave:1
Name:AX8640-0000-0103
Output size: 0bits
Input size: 16bits
State: 18
Delay: 0[ns]
Has DC: 1
DCParentport:0
Activeports:1.1.0.0
Configured address: 1001
Man: 00000002 ID: 21c06012 Rev: 00670000
SM0 A:1000 L: 256 F:00010026 Type:1
SM1 A:1100 L: 256 F:00010022 Type:2
SM2 A:1200 L: 0 F:00000004 Type:3
SM3 A:1900 L: 2 F:00010020 Type:4
FMMU0 Ls:0000002c Ll: 2 Lsb:0 Leb:7 Ps:1900 Psb:0 Ty:01 Act:01
FMMUfunc 0:2 1:3 2:0 3:0
MBX length wr: 128 rd: 128 MBX protocols : 0c
CoE details: 27 FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0
PDO mapping according to CoE :

Slave:2
Name:AX8206-0000-0103
Output size: 176bits
Input size: 176bits
State: 18
Delay: 175[ns]
Has DC: 1
DCParentport:1
Activeports:1.1.0.0
Configured address: 1002
Man: 00000002 ID: 200e6012 Rev: 00670000
SM0 A:1000 L: 512 F:00010026 Type:1
SM1 A:1400 L: 512 F:00010022 Type:2
SM2 A:1800 L: 22 F:00010064 Type:3
SM3 A:2a00 L: 22 F:00010020 Type:4
SM4 A:3c00 L: 0 F:00000024 Type:5
SM5 A:4e00 L: 0 F:00000020 Type:6
FMMU0 Ls:00000000 Ll: 22 Lsb:0 Leb:7 Ps:1800 Psb:0 Ty:02 Act:01
FMMU1 Ls:0000002e Ll: 22 Lsb:0 Leb:7 Ps:2a00 Psb:0 Ty:01 Act:01
FMMUfunc 0:1 1:2 2:3 3:5
MBX length wr: 512 rd: 512 MBX protocols : 0d
CoE details: 2f FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0
PDO mapping according to CoE :
SM2 outputs
addr b index: sub bitl data_type name
[0x0000.0] 0x2C00:0x01 0x10 UNSIGNED16 Power supply controlword
[0x0002.0] 0x6040:0x00 0x10 UNSIGNED16 Ch A Controlword
[0x0004.0] 0x607A:0x00 0x20 INTEGER32 Ch A Target position
[0x0008.0] 0x60FF:0x00 0x20 INTEGER32 Ch A Target velocity
[0x000C.0] 0x6840:0x00 0x10 UNSIGNED16 Ch B Controlword
[0x000E.0] 0x687A:0x00 0x20 INTEGER32 Ch B Target position
[0x0012.0] 0x68FF:0x00 0x20 INTEGER32 Ch B Target velocity
SM3 inputs
addr b index: sub bitl data_type name
[0x002E.0] 0x0000:0x00 0x01
[0x002E.1] 0x603E:0x02 0x01 BOOLEAN Position actual value invalid
[0x002E.2] 0x603E:0x03 0x01 BOOLEAN 1st Additional position actual value inv
[0x002E.3] 0x0000:0x00 0x05
[0x002F.0] 0x6041:0x00 0x10 UNSIGNED16 Ch A Statusword
[0x0031.0] 0x6064:0x00 0x20 INTEGER32 Ch A Position actual value
[0x0035.0] 0x60F4:0x00 0x20 INTEGER32 Ch A Following error actual value
[0x0039.0] 0x0000:0x00 0x01
[0x0039.1] 0x683E:0x02 0x01 BOOLEAN Position actual value invalid
[0x0039.2] 0x683E:0x03 0x01 BOOLEAN 1st Additional position actual value inv
[0x0039.3] 0x0000:0x00 0x05
[0x003A.0] 0x6841:0x00 0x10 UNSIGNED16 Ch B Statusword
[0x003C.0] 0x6864:0x00 0x20 INTEGER32 Ch B Position actual value
[0x0040.0] 0x68F4:0x00 0x20 INTEGER32 Ch B Following error actual value

Slave:3
Name:AX8206-0000-0103
Output size: 176bits
Input size: 176bits
State: 18
Delay: 390[ns]
Has DC: 1
DCParentport:1
Activeports:1.0.0.0
Configured address: 1003
Man: 00000002 ID: 200e6012 Rev: 00670000
SM0 A:1000 L: 512 F:00010026 Type:1
SM1 A:1400 L: 512 F:00010022 Type:2
SM2 A:1800 L: 22 F:00010064 Type:3
SM3 A:2a00 L: 22 F:00010020 Type:4
SM4 A:3c00 L: 0 F:00000024 Type:5
SM5 A:4e00 L: 0 F:00000020 Type:6
FMMU0 Ls:00000016 Ll: 22 Lsb:0 Leb:7 Ps:1800 Psb:0 Ty:02 Act:01
FMMU1 Ls:00000044 Ll: 22 Lsb:0 Leb:7 Ps:2a00 Psb:0 Ty:01 Act:01
FMMUfunc 0:1 1:2 2:3 3:5
MBX length wr: 512 rd: 512 MBX protocols : 0d
CoE details: 2f FoE details: 01 EoE details: 00 SoE details: 00
Ebus current: 0[mA]
only LRD/LWR:0
PDO mapping according to CoE :
SM2 outputs
addr b index: sub bitl data_type name
[0x0016.0] 0x2C00:0x01 0x10 UNSIGNED16 Power supply controlword
[0x0018.0] 0x6040:0x00 0x10 UNSIGNED16 Ch A Controlword
[0x001A.0] 0x607A:0x00 0x20 INTEGER32 Ch A Target position
[0x001E.0] 0x60FF:0x00 0x20 INTEGER32 Ch A Target velocity
[0x0022.0] 0x6840:0x00 0x10 UNSIGNED16 Ch B Controlword
[0x0024.0] 0x687A:0x00 0x20 INTEGER32 Ch B Target position
[0x0028.0] 0x68FF:0x00 0x20 INTEGER32 Ch B Target velocity
SM3 inputs
addr b index: sub bitl data_type name
[0x0044.0] 0x0000:0x00 0x01
[0x0044.1] 0x603E:0x02 0x01 BOOLEAN Position actual value invalid
[0x0044.2] 0x603E:0x03 0x01 BOOLEAN 1st Additional position actual value inv
[0x0044.3] 0x0000:0x00 0x05
[0x0045.0] 0x6041:0x00 0x10 UNSIGNED16 Ch A Statusword
[0x0047.0] 0x6064:0x00 0x20 INTEGER32 Ch A Position actual value
[0x004B.0] 0x60F4:0x00 0x20 INTEGER32 Ch A Following error actual value
[0x004F.0] 0x0000:0x00 0x01
[0x004F.1] 0x683E:0x02 0x01 BOOLEAN Position actual value invalid
[0x004F.2] 0x683E:0x03 0x01 BOOLEAN 1st Additional position actual value inv
[0x004F.3] 0x0000:0x00 0x05
[0x0050.0] 0x6841:0x00 0x10 UNSIGNED16 Ch B Statusword
[0x0052.0] 0x6864:0x00 0x20 INTEGER32 Ch B Position actual value
[0x0056.0] 0x68F4:0x00 0x20 INTEGER32 Ch B Following error actual value
End slaveinfo, close socket
End program

3 slaves found and configured.
Slaves mapped, state to SAFE_OP.
segments : 1 : 90 0 0 0
Request operational state for all slaves
Calculated workcounter 7
Not all slaves reached operational state.
Slave 1 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration
Slave 2 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration
Slave 3 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration

Request init state for all slaves
End simple test, close socket
End program

3_slave_BeckhOFF_with_CNC_and_NO_IO.zip

@ahmetihsankose ahmetihsankose changed the title Soem master using with bewckhoff driver Soem master using with beckhoff driver Nov 17, 2022
@ArthurKetels
Copy link
Contributor

These slaves require synchronized operation. This means distribute clocks, set the SYNC0/1 to fire at correct intervals and have the master PDO cycle synchronized. SOEM does not do this automatically. You have to write code to make that happen.

To have stable and reliable real-time communication with servo slaves see the many older posts about this subject. One I recommend is #487 (comment)

If you have a ENI file with a correct configuration you can use this as a template for coding this with SOEM.

@ahmetihsankose
Copy link
Author

thank you
I solved this problem according to your post.
Now, all my slaves ec status is working without error. They are all in OP mode.
But when i tried to read pdo messages i couldn't read anything. Then when I try to run the drivers with the twincat program, I noticed that without installing the Twincat driver manager, these salves not working properly.
When i install the drive manger, added more settings in Twincat startup settings. Most of these settings are motor related settings. But, it seems impossible for me to enter all of these settings manually :)

My question is, do I have to enter all these settings for master to work correctly?

The Eni file containing these settings is attached.
Thanks in advance.
ENI.zip
hed.

@ArthurKetels
Copy link
Contributor

You do not have to send all these commands to the slave. Most important are the PreOP to SafeOP transition settings. This means configuring the PDO mapping and also all motor and encoder parameters. Still quite a bit. But this is the way Beckhoff servo slaves are configured. Data is stored in the master and not in the slave. Therefore you have to write a whole bunch of data to each slave before it can operate.

An example :

                                                <InitCmd>
							<Transition>PS</Transition>
							<Comment><![CDATA[Ch A Motor parameters / Configured motor type]]></Comment>
							<Timeout>0</Timeout>
							<Ccs>1</Ccs>
							<Index>12992</Index>
							<SubIndex>1</SubIndex>
							<Data>414d383034312d78447830</Data>
						</InitCmd>

You have to write to SDO index 0x32c0:01 the data 414d383034312d78447830 (hex array in Complete Access mode). So this is still quite a bit of work. The ideal situation would be if you program your own configurator for this drive. An other solution is to write a ENI parser.

@ahmetihsankose
Copy link
Author

You do not have to send all these commands to the slave. Most important are the PreOP to SafeOP transition settings. This means configuring the PDO mapping and also all motor and encoder parameters. Still quite a bit. But this is the way Beckhoff servo slaves are configured. Data is stored in the master and not in the slave. Therefore you have to write a whole bunch of data to each slave before it can operate.

An example :

                                            <InitCmd>
  					<Transition>PS</Transition>
  					<Comment><![CDATA[Ch A Motor parameters / Configured motor type]]></Comment>
  					<Timeout>0</Timeout>
  					<Ccs>1</Ccs>
  					<Index>12992</Index>
  					<SubIndex>1</SubIndex>
  					<Data>414d383034312d78447830</Data>
  				</InitCmd>

You have to write to SDO index 0x32c0:01 the data 414d383034312d78447830 (hex array in Complete Access mode). So this is still quite a bit of work. The ideal situation would be if you program your own configurator for this drive. An other solution is to write a ENI parser.

Complete access mode will help.
I don't have the ability and time to write eni file parser for now.
Thank you very much for the answers, I will start communicating with the slaves tomorrow hopefully. :)

@ahmetihsankose
Copy link
Author

ahmetihsankose commented Nov 30, 2022

Hello,
ENI parser was not as difficult as I thought. I decided to write it but I have problems with sending data.
I don't fully understand full access mode. According to ENI file , some attributes of init cmds indicate CA = true, but most of init cmds attribute specify nothing like in the example you gave.
// can i write it like this ->
uint8_t hex_array[11] = {0x41, 0x4d, 0x38, 0x30, 0x,34, 0x31, 0x2d, 0x78, 0x44, 0x78, 0x30};
ec_SDOwrite(slave, 0x32c0, 0x01, TRUE, sizeof(hex_array), &hex_array, EC_TIMEOUTRXM);

When I look at the example below

<InitCmd Fixed="true" CompleteAccess="true">
<Transition>PS</Transition>
<Comment>
<![CDATA[ download pdo 0x1A26 entries ]]>
</Comment>
<Timeout>0</Timeout>
<Ccs>1</Ccs>
<Index>6694</Index>
<SubIndex>0</SubIndex>
<Data>01002000f460</Data>
</InitCmd>

I understand that there is a certain rule abaout Data
Data: 60f4 00 20 0001 (when i look reverse couple data)
Data: Index, subindex, size and length of entry.
But data of 0x32c0:01 means nothing to me.
Maybe my question be a little off topic. Actually i am not a native programmer. i am a very new.
Can you help abaout this issue, If there is any document abaout this issue, it will suffice as well.
Thanks in advance.

@ArthurKetels
Copy link
Contributor

All this information you can find in the official ETG document ETG.2100 S (R) V1.0.1 on www.ethercat.org

@ahmetihsankose
Copy link
Author

ahmetihsankose commented May 25, 2023

I apologize for the long delay. I wasn't able to attend to this topic, but I've decided to revisit it after a long time. I want to run these slaves with soem.
For distributed clock settings, i checked the eni file
and my locig like this. (The Ethercat_Master just a class is wrapping the SOEM library, and the Slave::slaveObjVector is holding the parsed data from the ENI file)

        ecx_configdc(Ethercat_Master::get_context());

	for (int slv = 1; slv <= Ethercat_Master::get_slave_count(); slv++)
	{
		if (Slave::slaveObjVector[slv]->dc.supported == TRUE &&
			Slave::slaveObjVector[slv]->dc.ReferenceClock == FALSE)
		{
			printf("DC is enabled\n");

			ecx_dcsync01(Ethercat_Master::get_context(), slv,
						 TRUE,
						 Slave::slaveObjVector[slv]->dc.CycleTime0,
						 Slave::slaveObjVector[slv]->dc.CycleTime1,
						 Slave::slaveObjVector[slv]->dc.ShiftTime);
			printf("DC is configured\n");
		}
		else if (Slave::slaveObjVector[slv]->dc.supported == TRUE &&
				 Slave::slaveObjVector[slv]->dc.ReferenceClock == TRUE)
		{
			printf("DC is enabled\n");

			ecx_dcsync0(Ethercat_Master::get_context(), slv,
						TRUE,
						Slave::slaveObjVector[slv]->dc.CycleTime0,
						Slave::slaveObjVector[slv]->dc.ShiftTime);
			printf("DC is configured\n");
		}
		else
		{
			printf("DC is disabled\n");
		}
	}

I am configuring the SDO settings for the slaves. I see that there are two initial settings specified in the ENI file for the power supply slave, labeled as PS and CoE. However, both of these settings are returning a WKC value of -5.The other two slaves have been successfully configured with the proper initial settings.

The result is that when I put the master into operational mode with using soem, the EtherCAT state of the power supply slave returns 20, while the state of the other two slaves returns 8.

The commands where I encountered errors while configuring the initial settings for the power supply are as follows.

<CoE>
<InitCmds>
<InitCmd Fixed="true" CompleteAccess="true">
<Transition>PS</Transition>
<Comment>
<![CDATA[ download pdo 0x1C12 index ]]>
</Comment>
<Timeout>0</Timeout>
<Ccs>1</Ccs>
<Index>7186</Index>
<SubIndex>0</SubIndex>
<Data>0000</Data>
</InitCmd>
<InitCmd Fixed="true" CompleteAccess="true">
<Transition>PS</Transition>
<Comment>
<![CDATA[ download pdo 0x1C13 index ]]>
</Comment>
<Timeout>0</Timeout>
<Ccs>1</Ccs>
<Index>7187</Index>
<SubIndex>0</SubIndex>
<Data>0100001a</Data>
</InitCmd

@ArthurKetels
Copy link
Contributor

Can you post the wirshark capture (in .pcap format) of the init sequence?

@ahmetihsankose
Copy link
Author

wireshark.zip this is my wireshark data of the init sequence.

@ahmetihsankose
Copy link
Author

ahmetihsankose commented Jun 22, 2023

i have still errors while setting up PDO messages. Specifically, all settings for the first slave power supply is returning a WKC of -5. However, after the initialization is complete, the EtherCAT state remains in error. After that, i use check_ethercat_state function from your example and the slaves can only reach to SafeOp state. Even then, the inputs and outputs in SOEM's slave struct still return nullptr.

When I looked at TwinCAT, I noticed that it continuously writes the control_word_axis struct data, which is at the input of the power supply, to the control_word_axis PDO message that is the output of each axis slave.

this is red_test result delay = 0.1 but still Invalid DC SYNC configuration.

SOEM (Simple Open EtherCAT Master)
Redundancy test
Starting Redundant test
ec_init on eno1 succeeded.
3 slaves found and configured.
Slave:1 Name:AX8640-0000-0103 Output size: 0bits Input size: 16bits State:18 delay:0.1
Out:(nil), 0 In:0x56339717914c, 2
Slave:2 Name:AX8206-0000-0103 Output size:176bits Input size:176bits State:18 delay:0.1
Out:0x563397179120, 22 In:0x56339717914e, 22
Slave:3 Name:AX8206-0000-0103 Output size:176bits Input size:176bits State:18 delay:0.1
Out:0x563397179136, 22 In:0x563397179164, 22
Calculated workcounter 7
Request operational state for all slaves
Not all slaves reached operational state.
Slave 1 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration
Slave 2 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration
Slave 3 State=0x12 StatusCode=0x0030 : Invalid DC SYNC configuration
Request safe operational state for all slaves
End redundant test, close socket
End program

beckhoff_wireshark_data.zip

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants