Skip to content

Commit c26fe06

Browse files
authored
Add Epos4 configuration example + small updates (README and epos3 comments in cfg file) (#18)
* Update contact in README.md * More precise about comments (PDO mapping) in epos3 configuration file. * Add epos4 50/5 configuration file example.
1 parent 7d9d717 commit c26fe06

File tree

3 files changed

+77
-26
lines changed

3 files changed

+77
-26
lines changed

README.md

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,4 +14,10 @@ This repository contains the following example packages :
1414

1515
[ICube Laboratory](https://icube.unistra.fr), [University of Strasbourg](https://www.unistra.fr/), France
1616

17+
__Manuel Yguel:__ [[email protected]](mailto:[email protected]), @github: [yguel](https://github.com/yguel)
18+
19+
__Laurent Barbé:__ [[email protected]](mailto:[email protected])
20+
21+
__Philippe Zanne:__ [[email protected]](mailto:[email protected])
22+
1723
__Maciej Bednarczyk:__ [[email protected]](mailto:[email protected]), @github: [mcbed](https://github.com/mcbed)
Lines changed: 32 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -1,33 +1,39 @@
11
# Configuration file for Maxon EPOS3 drive
22
vendor_id: 0x000000fb
33
product_id: 0x64400000
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-
sdo: # sdo data to be transferred at drive startup
7-
- {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms
8-
- {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s
9-
rpdo: # RxPDO = receive PDO Mapping
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+
sdo: # sdo data to be transferred at drive startup
7+
- { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
8+
- { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
9+
rpdo: # RxPDO = receive PDO 4 Mapping
1010
- index: 0x1603
1111
channels:
12-
- {index: 0x6040, sub_index: 0, type: uint16, default: 0} # Control word
13-
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
14-
- {index: 0x60ff, sub_index: 0, type: int32, default: 0} # Target velocity
15-
- {index: 0x6071, sub_index: 0, type: int16, default: 0} # Target torque
16-
- {index: 0x60b0, sub_index: 0, type: int32, default: 0} # Offset position
17-
- {index: 0x60b1, sub_index: 0, type: int32, default: 0} # Offset velocity
18-
- {index: 0x60b2, sub_index: 0, type: int16, default: 0} # Offset torque
19-
- {index: 0x6060, sub_index: 0, type: int8, default: 8} # Mode of operation
20-
- {index: 0x2078, sub_index: 1, type: uint16, default: 0} # Digital Output Functionalities
21-
- {index: 0x60b8, sub_index: 0, type: uint16, default: 0} # Touch Probe Function
22-
tpdo: # TxPDO = transmit PDO Mapping
12+
- { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
13+
- {
14+
index: 0x607a,
15+
sub_index: 0,
16+
type: int32,
17+
command_interface: position,
18+
default: .nan,
19+
} # Target position
20+
- { index: 0x60ff, sub_index: 0, type: int32, default: 0 } # Target velocity
21+
- { index: 0x6071, sub_index: 0, type: int16, default: 0 } # Target torque
22+
- { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position
23+
- { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity
24+
- { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque
25+
- { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
26+
- { index: 0x2078, sub_index: 1, type: uint16, default: 0 } # Digital Output Functionalities
27+
- { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch Probe Function
28+
tpdo: # TxPDO = transmit PDO 4 Mapping
2329
- index: 0x1a03
2430
channels:
25-
- {index: 0x6041, sub_index: 0, type: uint16} # Status word
26-
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
27-
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value
28-
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort} # Torque actual value
29-
- {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
30-
- {index: 0x2071, sub_index: 1, type: int16} # Digital Input Functionalities State
31-
- {index: 0x60b9, sub_index: 0, type: int16} # Touch Probe Status
32-
- {index: 0x60ba, sub_index: 0, type: int32} # Touch Probe Position 1 Positive Value
33-
- {index: 0x60bb, sub_index: 0, type: int32} # Touch Probe Position 1 Negative Value
31+
- { index: 0x6041, sub_index: 0, type: uint16 } # Status word
32+
- { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Position actual value
33+
- { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Velocity actual value
34+
- { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Torque actual value
35+
- { index: 0x6061, sub_index: 0, type: int8 } # Mode of operation display
36+
- { index: 0x2071, sub_index: 1, type: int16 } # Digital Input Functionalities State
37+
- { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
38+
- { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive Value
39+
- { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative Value
Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
# Configuration file for Maxon EPOS4 50/5 drive
2+
vendor_id: 0x000000fb
3+
product_id: 0x63500000 # Product code
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+
sdo: # sdo data to be transferred at drive startup
7+
- { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
8+
- { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
9+
rpdo: # RxPDO = receive PDO 4 Mapping
10+
- index: 0x1603
11+
channels:
12+
- { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
13+
- {
14+
index: 0x607a,
15+
sub_index: 0,
16+
type: int32,
17+
command_interface: position,
18+
default: .nan,
19+
} # Target position
20+
- { index: 0x60ff, sub_index: 0, type: int32, default: 0 } # Target velocity
21+
- { index: 0x6071, sub_index: 0, type: int16, default: 0 } # Target torque
22+
- { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position
23+
- { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity
24+
- { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque
25+
- { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
26+
- { index: 0x3150, sub_index: 1, type: uint16, default: 0 } # Digital Output Properties
27+
- { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch Probe Function
28+
tpdo: # TxPDO = transmit PDO 4 Mapping
29+
- index: 0x1a03
30+
channels:
31+
- { index: 0x6041, sub_index: 0, type: uint16 } # Status word
32+
- { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Position actual value
33+
- { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Velocity actual value
34+
- { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Torque actual value
35+
- { index: 0x6061, sub_index: 0, type: int8 } # Mode of operation display
36+
- { index: 0x3141, sub_index: 1, type: int16 } # Digital Input Properties
37+
- { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
38+
- { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive edge
39+
- { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative edge

0 commit comments

Comments
 (0)