Skip to content

Commit

Permalink
Add Epos4 configuration example + small updates (README and epos3 com…
Browse files Browse the repository at this point in the history
…ments 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.
  • Loading branch information
yguel authored Jul 3, 2024
1 parent 7d9d717 commit c26fe06
Show file tree
Hide file tree
Showing 3 changed files with 77 additions and 26 deletions.
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,10 @@ This repository contains the following example packages :

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

__Manuel Yguel:__ [[email protected]](mailto:[email protected]), @github: [yguel](https://github.com/yguel)

__Laurent Barbé:__ [[email protected]](mailto:[email protected])

__Philippe Zanne:__ [[email protected]](mailto:[email protected])

__Maciej Bednarczyk:__ [[email protected]](mailto:[email protected]), @github: [mcbed](https://github.com/mcbed)
58 changes: 32 additions & 26 deletions ethercat_motor_drive/config/maxon_epos3_config.yaml
Original file line number Diff line number Diff line change
@@ -1,33 +1,39 @@
# Configuration file for Maxon EPOS3 drive
vendor_id: 0x000000fb
product_id: 0x64400000
assign_activate: 0x0300 # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
- {index: 0x60C2, sub_index: 1, type: int8, value: 10} # Set interpolation time for cyclic modes to 10 ms
- {index: 0x60C2, sub_index: 2, type: int8, value: -3} # Set base 10-3s
rpdo: # RxPDO = receive PDO Mapping
assign_activate: 0x0300 # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
- { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
- { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO = receive PDO 4 Mapping
- index: 0x1603
channels:
- {index: 0x6040, sub_index: 0, type: uint16, default: 0} # Control word
- {index: 0x607a, sub_index: 0, type: int32, command_interface: position, default: .nan} # Target position
- {index: 0x60ff, sub_index: 0, type: int32, default: 0} # Target velocity
- {index: 0x6071, sub_index: 0, type: int16, default: 0} # Target torque
- {index: 0x60b0, sub_index: 0, type: int32, default: 0} # Offset position
- {index: 0x60b1, sub_index: 0, type: int32, default: 0} # Offset velocity
- {index: 0x60b2, sub_index: 0, type: int16, default: 0} # Offset torque
- {index: 0x6060, sub_index: 0, type: int8, default: 8} # Mode of operation
- {index: 0x2078, sub_index: 1, type: uint16, default: 0} # Digital Output Functionalities
- {index: 0x60b8, sub_index: 0, type: uint16, default: 0} # Touch Probe Function
tpdo: # TxPDO = transmit PDO Mapping
- { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
- {
index: 0x607a,
sub_index: 0,
type: int32,
command_interface: position,
default: .nan,
} # Target position
- { index: 0x60ff, sub_index: 0, type: int32, default: 0 } # Target velocity
- { index: 0x6071, sub_index: 0, type: int16, default: 0 } # Target torque
- { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position
- { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity
- { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque
- { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
- { index: 0x2078, sub_index: 1, type: uint16, default: 0 } # Digital Output Functionalities
- { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch Probe Function
tpdo: # TxPDO = transmit PDO 4 Mapping
- index: 0x1a03
channels:
- {index: 0x6041, sub_index: 0, type: uint16} # Status word
- {index: 0x6064, sub_index: 0, type: int32, state_interface: position} # Position actual value
- {index: 0x606c, sub_index: 0, type: int32, state_interface: velocity} # Velocity actual value
- {index: 0x6077, sub_index: 0, type: int16, state_interface: effort} # Torque actual value
- {index: 0x6061, sub_index: 0, type: int8} # Mode of operation display
- {index: 0x2071, sub_index: 1, type: int16} # Digital Input Functionalities State
- {index: 0x60b9, sub_index: 0, type: int16} # Touch Probe Status
- {index: 0x60ba, sub_index: 0, type: int32} # Touch Probe Position 1 Positive Value
- {index: 0x60bb, sub_index: 0, type: int32} # Touch Probe Position 1 Negative Value
- { index: 0x6041, sub_index: 0, type: uint16 } # Status word
- { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Position actual value
- { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Velocity actual value
- { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Torque actual value
- { index: 0x6061, sub_index: 0, type: int8 } # Mode of operation display
- { index: 0x2071, sub_index: 1, type: int16 } # Digital Input Functionalities State
- { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
- { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive Value
- { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative Value
39 changes: 39 additions & 0 deletions ethercat_motor_drive/config/maxon_epos4_50_5_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
# Configuration file for Maxon EPOS4 50/5 drive
vendor_id: 0x000000fb
product_id: 0x63500000 # Product code
assign_activate: 0x0300 # DC Synch register
auto_fault_reset: false # true = automatic fault reset, false = fault reset on rising edge command interface "reset_fault"
sdo: # sdo data to be transferred at drive startup
- { index: 0x60C2, sub_index: 1, type: int8, value: 10 } # Set interpolation time for cyclic modes to 10 ms
- { index: 0x60C2, sub_index: 2, type: int8, value: -3 } # Set base 10-3s
rpdo: # RxPDO = receive PDO 4 Mapping
- index: 0x1603
channels:
- { index: 0x6040, sub_index: 0, type: uint16, default: 0 } # Control word
- {
index: 0x607a,
sub_index: 0,
type: int32,
command_interface: position,
default: .nan,
} # Target position
- { index: 0x60ff, sub_index: 0, type: int32, default: 0 } # Target velocity
- { index: 0x6071, sub_index: 0, type: int16, default: 0 } # Target torque
- { index: 0x60b0, sub_index: 0, type: int32, default: 0 } # Offset position
- { index: 0x60b1, sub_index: 0, type: int32, default: 0 } # Offset velocity
- { index: 0x60b2, sub_index: 0, type: int16, default: 0 } # Offset torque
- { index: 0x6060, sub_index: 0, type: int8, default: 8 } # Mode of operation
- { index: 0x3150, sub_index: 1, type: uint16, default: 0 } # Digital Output Properties
- { index: 0x60b8, sub_index: 0, type: uint16, default: 0 } # Touch Probe Function
tpdo: # TxPDO = transmit PDO 4 Mapping
- index: 0x1a03
channels:
- { index: 0x6041, sub_index: 0, type: uint16 } # Status word
- { index: 0x6064, sub_index: 0, type: int32, state_interface: position } # Position actual value
- { index: 0x606c, sub_index: 0, type: int32, state_interface: velocity } # Velocity actual value
- { index: 0x6077, sub_index: 0, type: int16, state_interface: effort } # Torque actual value
- { index: 0x6061, sub_index: 0, type: int8 } # Mode of operation display
- { index: 0x3141, sub_index: 1, type: int16 } # Digital Input Properties
- { index: 0x60b9, sub_index: 0, type: int16 } # Touch Probe Status
- { index: 0x60ba, sub_index: 0, type: int32 } # Touch Probe Position 1 Positive edge
- { index: 0x60bb, sub_index: 0, type: int32 } # Touch Probe Position 1 Negative edge

0 comments on commit c26fe06

Please sign in to comment.