Skip to content

Commit 7d9d717

Browse files
authored
Add Synapticon Circulo 9 Config (#16)
* add synaption config * add synapticon description * fix synapticon data types
1 parent aef67fc commit 7d9d717

File tree

2 files changed

+54
-0
lines changed

2 files changed

+54
-0
lines changed

ethercat_slave_description/README.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -43,3 +43,7 @@ The list of available example EtherCAT motor drive module configurations for the
4343
### Technosoft
4444
- **Technosoft IPOS 3604**: Technosoft IPOS 3064 motor drive.
4545
- Plugin : `EcCiA402Drive`
46+
47+
### Synapticon
48+
- **Synapticon SOMANET Circulo 9**: Synapticon SOMANET Circulo 9 Safe Motion servo drive.
49+
- Plugin : `EcCiA402Drive`
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
# Configuration file for Synapticon SOMANET Circulo 9 Safe Motion, Firmware Version 5.1.3
2+
vendor_id: 0x000022d2
3+
product_id: 0x00000302
4+
assign_activate: 0x0300 # DC Synch register
5+
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
6+
rpdo: # RxPDO = receive PDO Mapping
7+
- index: 0x1600
8+
channels:
9+
- {index: 0x6040, sub_index: 0, type: uint16, default: 0} # Control word
10+
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
11+
- {index: 0x60ff, sub_index: 0, type: int32, default: 0} # Target velocity
12+
- {index: 0x6071, sub_index: 0, type: int16, default: 0} # Target torque
13+
- {index: 0x60b2, sub_index: 0, type: int16, default: 0} # Offset torque
14+
- {index: 0x6060, sub_index: 0, type: int8, default: 8} # Mode of operation
15+
- {index: 0x2701, sub_index: 0, type: uint32, default: 0} # Tuning command
16+
- index: 0x1601
17+
channels:
18+
- {index: 0x60fe, sub_index: 1, type: uint32, default: 0} # Digital Outputs: Physical Outputs
19+
- {index: 0x60fe, sub_index: 2, type: uint32, default: 0} # Digital Outputs: Bit Mask
20+
- index: 0x1602
21+
channels:
22+
- {index: 0x60b1, sub_index: 0, type: int32, default: 0} # Offset velocity
23+
- {index: 0x2703, sub_index: 0, type: uint32, default: 0} # User MOSI
24+
25+
tpdo: # TxPDO = transmit PDO Mapping
26+
- index: 0x1a00
27+
channels:
28+
- {index: 0x6041, sub_index: 0, type: uint16} # Status word
29+
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
30+
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value
31+
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort} # Torque actual value
32+
- {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
33+
- {index: 0x60f4, sub_index: 0, type: int32} # Following error actual value
34+
- index: 0x1a01
35+
channels:
36+
- {index: 0x2401, sub_index: 0, type: uint16} # Analog input 1
37+
- {index: 0x2402, sub_index: 0, type: uint16} # Analog input 2
38+
- {index: 0x2403, sub_index: 0, type: uint16} # Analog input 3
39+
- {index: 0x2404, sub_index: 0, type: uint16} # Analog input 4
40+
- {index: 0x2702, sub_index: 0, type: uint32} # Tuning status
41+
- index: 0x1a02
42+
channels:
43+
- {index: 0x60fd, sub_index: 0, type: uint32} # Digital Inputs
44+
- index: 0x1a03
45+
channels:
46+
- {index: 0x2704, sub_index: 0, type: uint32} # User MISO
47+
- {index: 0x20f0, sub_index: 0, type: uint32} # Timestamp
48+
- {index: 0x60fc, sub_index: 0, type: int32} # Position demand internal value
49+
- {index: 0x606b, sub_index: 0, type: int32} # Velocity demand value
50+
- {index: 0x6074, sub_index: 0, type: int16} # Torque demand

0 commit comments

Comments
 (0)