Skip to content

Commit 11896a9

Browse files
Prepare 0.1.0 release (#20)
1 parent f7a0500 commit 11896a9

File tree

8 files changed

+200
-218
lines changed

8 files changed

+200
-218
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
cmake_minimum_required(VERSION 3.8...3.30)
55
project(
66
yarp-device-ethercat-cia402 # project name
7-
VERSION 1.0.0 # bump as you tag releases
7+
VERSION 0.1.0 # bump as you tag releases
88
DESCRIPTION "YARP device plugin for EtherCAT CiA402 drives"
99
LANGUAGES CXX
1010
)

README.md

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ export YARP_DATA_DIRS=/path/to/install:$YARP_DATA_DIRS
5050
```
5151

5252
### Configuration ⚙️
53-
The plugin requires a configuration file defining the EtherCAT network and device parameters. An example can be found at: [`config/robot/adj8/config.xml`](config/robot/adj8/config.xml)
53+
The plugin requires a configuration file defining the EtherCAT network and device parameters. An example can be found at: [`config/robot/template_1_motor/config.xml`](config/robot/template_1_motor/config.xml)
5454

5555
### Setting Up `yarprobotinterface` 🛠️
5656
To ensure that the `yarprobotinterface` binary has the correct permissions and can locate its dependencies, execute:
@@ -71,10 +71,12 @@ This plugin has been primarily tested with Synapticon drives. While it may be co
7171

7272
If you're looking to adapt the plugin for different hardware, we encourage you to open an issue or contribute improvements.
7373

74-
### Note on PDO Mapping 📝
75-
The plugin includes a custom mapping of the **Safe Torque Off (STO)** and **Safe Brake Control (SBC)** signals into PDOs. This design choice enables the EtherCAT master to access real-time data on these critical safety features, enhancing runtime monitoring and safety state management.
74+
### Additional notes 📝
75+
For more details, see:
76+
- Protocol map — PDOs, SDOs, and conversion formulas: [doc/protocol_map.md](./doc/protocol_map.md)
77+
- Modes and setpoints — available control modes and targets: [doc/modes_and_setpoints.md](./doc/modes_and_setpoints.md)
78+
- Dual encoder handling — mounts, sources, and transformations: [doc/dual_encoder_handling.md](./doc/dual_encoder_handling.md)
7679

77-
Although this approach diverges from strict CiA402 compliance, it brings practical advantages: improved fault detection, smoother safety transitions, and more robust motion control. The mapping is handled by the `configurePDOMapping` method in the `EthercatManager` class, ensuring that STO and SBC statuses are continuously updated and readily available for real-time decision-making.
7880

7981
## License 📜
8082
This project is licensed under the BSD-3-Clause License. See the [`LICENSE`](LICENSE) file for details.
Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,7 @@ BSD-3-Clause license. -->
55
<?xml version="1.0" encoding="UTF-8" ?>
66
<!DOCTYPE robot PUBLIC "-//YARP//DTD yarprobotinterface 3.0//EN" "http://www.yarp.it/DTD/yarprobotinterfaceV3.0.dtd">
77

8-
<robot name="adj8" portprefix="ethercat" build="1" xmlns:xi="http://www.w3.org/2001/XInclude">
8+
<robot name="template_1_motor" portprefix="ethercat" build="1" xmlns:xi="http://www.w3.org/2001/XInclude">
99
<xi:include href="./motion_control/all_joint_mc.xml" />
1010
<xi:include href="./motion_control/all_joint_mc_nws.xml" />
11-
1211
</robot>

config/robot/adj8/motion_control/all_joint_mc.xml renamed to config/robot/template_1_motor/motion_control/all_joint_mc.xml

File renamed without changes.

config/robot/adj8/motion_control/all_joint_mc_nws.xml renamed to config/robot/template_1_motor/motion_control/all_joint_mc_nws.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ BSD-3-Clause license. -->
44
<?xml version="1.0" encoding="UTF-8"?>
55
<device xmlns:xi="http://www.w3.org/2001/XInclude" name="all_joints_mc_nws_yarp" type="controlBoard_nws_yarp">
66
<param name="period"> 0.001 </param>
7-
<param name="name"> /adj8/motor </param>
7+
<param name="name"> /template/motor </param>
88
<action phase="startup" level="10" type="attach">
99
<param name="device"> all_joints_mc </param>
1010
</action>

doc/dual_encoder_handling.md

Lines changed: 75 additions & 210 deletions
Original file line numberDiff line numberDiff line change
@@ -1,145 +1,54 @@
1-
# Dual-encoder handling (CiA-402 EtherCAT device)
1+
# Dual-encoder handling (CiA402 EtherCAT device)
22

3-
This document describes how **`CiA402MotionControl`** and **`EthercatManager`** manage dual encoders per axis, how EtherCAT PDOs are mapped, and how values are converted into YARP’s expected units.
4-
It is intended as a **developer guide to the code**, with emphasis on configuration, feedback/command pipelines, and validation logic.
3+
## Summary
4+
How the driver uses two encoders per axis: mounting semantics, loop sources, feedback selection, shaft transforms, and data pipelines.
55

6-
---
76

8-
## 1) EtherCAT PDO mapping
9-
10-
PDO mapping is configured in `EthercatManager::configurePDOMapping`.
11-
12-
### RxPDO 0x1600 (Master → Slave, fixed)
13-
14-
| Object | Index | Size | Standard / Vendor | Notes |
15-
| ------------------ | --------- | ---- | ----------------- | --------------------------- |
16-
| Controlword | 0x6040:00 | 16 | **CiA-402** | Drive state machine control |
17-
| Modes of operation | 0x6060:00 | 8 | **CiA-402** | Op-mode command |
18-
| Target torque | 0x6071:00 | 16 | **CiA-402** | CST torque target |
19-
| Target position | 0x607A:00 | 32 | **CiA-402** | CSP / PP position target |
20-
| Target velocity | 0x60FF:00 | 32 | **CiA-402** | CSV velocity target |
21-
22-
---
23-
24-
### TxPDO 0x1A00… (Slave → Master, dynamic, rollover)
25-
26-
| Object | Index | Size | Standard / Vendor | Notes |
27-
| ---------------------------------- | --------- | ---- | ----------------------- | -------------------------- |
28-
| **Mandatory** | | | | |
29-
| Statusword | 0x6041:00 | 16 | **CiA-402** | Drive status bits |
30-
| OpMode display | 0x6061:00 | 8 | **CiA-402** | Current op-mode |
31-
| Position actual value | 0x6064:00 | 32 | **CiA-402** | Position (counts) |
32-
| Velocity actual value | 0x606C:00 | 32 | **CiA-402** | Velocity (rpm) |
33-
| Torque actual value | 0x6077:00 | 16 | **CiA-402** | Torque (permille of rated) |
34-
| Position error | 0x6065:00 | 32 | **CiA-402** | Internal error signal |
35-
| **Optional (mapped if available)** | | | | |
36-
| Timestamp | 0x20F0:00 | 32 | **Vendor (Synapticon)** | Drive µs timestamp |
37-
| STO status | 0x6621:01 | 8 | **Vendor (Synapticon)** | Safe Torque Off bit |
38-
| SBC status | 0x6621:02 | 8 | **Vendor (Synapticon)** | Safe Brake Control bit |
39-
| Enc1Pos | 0x2111:02 | 32 | **Vendor (Synapticon)** | Encoder 1 position |
40-
| Enc1Vel | 0x2111:03 | 32 | **Vendor (Synapticon)** | Encoder 1 velocity |
41-
| Enc2Pos | 0x2113:02 | 32 | **Vendor (Synapticon)** | Encoder 2 position |
42-
| Enc2Vel | 0x2113:03 | 32 | **Vendor (Synapticon)** | Encoder 2 velocity |
43-
44-
**Notes:**
45-
46-
* **CiA-402 standard objects** are guaranteed across compliant drives.
47-
* **Synapticon vendor objects** extend support for dual encoders, safety, and synchronization.
48-
* TxPDOs roll over into 0x1A01, 0x1A02… if >8 entries are required.
49-
50-
51-
## 2) Encoder mounting and drive loop sources
7+
## Quick reference
528

539
Configuration keys parsed in `CiA402MotionControl::open`:
5410

55-
| Key | Allowed values | Meaning |
56-
| ------------ | ------------------------ | ------------------------------ |
57-
| `enc1_mount` | `motor`, `joint` | Physical location of encoder 1 |
58-
| `enc2_mount` | `motor`, `joint`, `none` | Physical location of encoder 2 |
59-
60-
Drive reports its internal loop sources via SDOs:
61-
62-
| Loop | SDO index | Values |
63-
| -------------------- | --------- | ---------------------------- |
64-
| Position loop source | 0x2012:09 | 1=Enc1, 2=Enc2, else Unknown |
65-
| Velocity loop source | 0x2011:05 | 1=Enc1, 2=Enc2, else Unknown |
66-
67-
These determine how the **standard CiA-402 objects** (6064/606C) should be interpreted.
68-
69-
---
70-
71-
## 3) Feedback source selection
11+
| Key | Allowed values | Meaning |
12+
|---------------------------|----------------------------------|-----------------------------------------|
13+
| enc1_mount | `motor`, `joint` | Physical location of encoder 1 |
14+
| enc2_mount | `motor`, `joint`, `none` | Physical location of encoder 2 |
15+
| position_feedback_joint | `"6064"`, `"enc1"`, `"enc2"` | Source for joint position |
16+
| position_feedback_motor | `"6064"`, `"enc1"`, `"enc2"` | Source for motor position |
17+
| velocity_feedback_joint | `"606C"`, `"enc1"`, `"enc2"` | Source for joint velocity |
18+
| velocity_feedback_motor | `"606C"`, `"enc1"`, `"enc2"` | Source for motor velocity |
7219

73-
Configurable per axis:
20+
Notes:
21+
- `6064` = Position actual value; `606C` = Velocity actual value (details in protocol_map.md).
22+
- If a source is `enc1`/`enc2`, the encoder must be mounted and its PDO must be mapped.
7423

75-
| Feedback | Config key | Options |
76-
| -------------- | ------------------------- | ---------------------------- |
77-
| Joint position | `position_feedback_joint` | `"6064"`, `"enc1"`, `"enc2"` |
78-
| Motor position | `position_feedback_motor` | `"6064"`, `"enc1"`, `"enc2"` |
79-
| Joint velocity | `velocity_feedback_joint` | `"606C"`, `"enc1"`, `"enc2"` |
80-
| Motor velocity | `velocity_feedback_motor` | `"606C"`, `"enc1"`, `"enc2"` |
24+
## Drive loop sources
25+
The drive’s control loops run off an internal source selection for position and velocity. The driver reads the “position loop source” and “velocity loop source” SDOs (indices listed in protocol_map.md) to interpret what `6064/606C` refer to. If a loop source is unknown, a conservative fallback is used (prefer Enc1 if mounted, else Enc2).
8126

82-
**Validation (`open()`):**
27+
## Feedback source selection
28+
Validation performed during `open()`:
29+
- If `position/velocity_feedback_*` is `enc1`/`enc2`, that encoder must be mounted and present in the PDO map, otherwise configuration fails.
30+
- If the source is `6064/606C`, values are interpreted in the context of the loop source selection above.
8331

84-
* If a source = `enc1`/`enc2`, then:
85-
86-
* That encoder must be **mounted** and
87-
* Its PDO entry must be **mapped**.
88-
Otherwise: `invalid config: encX not mounted/mapped`.
89-
* If a source = `6064`/`606C`, values are interpreted according to `posLoopSrc` / `velLoopSrc`.
90-
If loop source is `Unknown`, fallback = Enc1 if present, else Enc2.
91-
92-
---
93-
94-
## 4) Units and conversions
95-
96-
* **Resolutions:**
97-
98-
* Enc1 CPR → 0x2110:03
99-
* Enc2 CPR → 0x2112:03
100-
101-
* **Gear ratio:**
102-
103-
* Numerator 0x6091:01, denominator 0x6091:02
104-
* `gearRatio = motor_revs / load_revs`
105-
* `gearRatioInv = 1 / gearRatio`
106-
107-
* **Conversions:**
108-
109-
| Source | Native | Conversion |
110-
| ------------------------ | ------------------------------ | ----------------------------------------------------- |
111-
| 0x6064, Enc1Pos, Enc2Pos | counts | × (360 / CPR) → degrees |
112-
| 0x606C, Enc1Vel, Enc2Vel | rpm | × 360/60 → deg/s |
113-
| 0x6077 | permille of rated motor torque | /1000 × ratedNm → motorNm; then × gearRatio → jointNm |
114-
115-
---
116-
117-
## 5) Shaft transformations
118-
119-
Transformation rules applied in `readFeedback`:
32+
## Shaft transformations
33+
When converting measurements between motor and joint shafts, the driver applies gear ratio–based transforms:
12034

12135
| From → To | Formula |
122-
| ------------- | ------------------ |
36+
|---------------|--------------------|
12337
| Motor → Motor | deg (unchanged) |
124-
| Motor → Joint | deg × gearRatioInv |
38+
| Motor → Joint | deg × 1/gearRatio |
12539
| Joint → Motor | deg × gearRatio |
12640
| Joint → Joint | deg (unchanged) |
12741

128-
Same for velocities.
129-
130-
---
131-
132-
## 6) Feedback pipeline
42+
Same logic applies to velocities.
13343

134-
Per axis:
135-
136-
1. **Select source** (config).
137-
2. **Convert raw**: counts→deg or rpm→deg/s on the encoder’s own shaft.
138-
3. **Transform** to requested shaft (motor/joint) via gear ratio + mount.
139-
4. **Store** into `variables` (protected by mutex).
140-
141-
Mermaid diagram (position feedback):
44+
## Feedback pipeline
45+
Per axis (conceptual):
46+
1. Select source (config).
47+
2. Convert raw → engineering units on the encoder’s own shaft (counts→deg or rpm→deg/s; formulas in protocol_map.md).
48+
3. Transform to the requested shaft (motor/joint) using gear ratio and mounts.
49+
4. Store into thread‑safe variables for YARP interfaces.
14250

51+
Mermaid (position path):
14352
```mermaid
14453
flowchart LR
14554
subgraph PDO[TxPDO raw sources]
@@ -164,89 +73,45 @@ flowchart LR
16473
```
16574

16675
Fallbacks:
167-
168-
* Unknown loop source → prefer Enc1 if mounted.
169-
* Accelerations → always `0.0`.
170-
* Safety bits (STO/SBC) and timestamp handled if PDO entries are present.
171-
172-
---
173-
174-
## 7) Command pipeline
175-
176-
Implemented in `setSetPoints`:
177-
178-
* **Torque mode (CST):**
179-
180-
* YARP joint torque \[Nm] → motorNm = jointNm / gearRatio
181-
* TargetTorque = round(motorNm / ratedMotorTorqueNm × 1000) (permille)
182-
* First-cycle latch sends `0`.
183-
184-
* **Velocity mode (CSV):**
185-
186-
* YARP joint velocity \[deg/s] → shaft velocity depends on `velLoopSrc` + mount.
187-
* shaft\_deg\_s × 60/360 → rpm.
188-
* TargetVelocity = round(rpm).
189-
* First-cycle latch sends `0`.
190-
191-
---
192-
193-
## 8) Valid config examples
194-
195-
1. **Motor encoder only**
196-
197-
* `enc1_mount=motor, enc2_mount=none`
198-
* joint feedback derived from Enc1 + gearRatioInv.
199-
200-
2. **Joint encoder only**
201-
202-
* `enc1_mount=none, enc2_mount=joint`
203-
* motor feedback derived via gearRatio.
204-
205-
3. **Dual (classical)**
206-
207-
* `enc1_mount=motor, enc2_mount=joint`
208-
* position\_joint=enc2, position\_motor=enc1
209-
* velocity\_joint=606C (if velLoopSrc=Enc2), velocity\_motor=606C or enc1.
210-
211-
4. **Redundant/diagnostic**
212-
213-
* both mounted; expose 6064/606C for drive loops, plus direct enc1/enc2 for cross-checks.
214-
215-
---
216-
217-
## 9) Edge cases & notes
218-
219-
* `gearRatio=0` → invalid; conversions return 0.
220-
* Sign conventions: assumed consistent; compensation must be external if not.
221-
* Backlash detection (motor vs joint encoder) is out of scope.
222-
* PDO rollover handled automatically; always check `TxView::has()` before access.
223-
224-
---
225-
226-
## 10) Object reference
227-
228-
| Object | Index | Type | Meaning |
229-
| ----------------- | --------- | ------ | ----------------- |
230-
| Position actual | 0x6064:00 | INT32 | counts |
231-
| Velocity actual | 0x606C:00 | INT32 | rpm |
232-
| Torque actual | 0x6077:00 | INT16 | permille of rated |
233-
| Rated torque | 0x6076:00 | UINT32 | mNm |
234-
| Max torque % | 0x6072:00 | UINT16 | permille of rated |
235-
| Enc1 resolution | 0x2110:03 | UINT32 | counts/rev |
236-
| Enc2 resolution | 0x2112:03 | UINT32 | counts/rev |
237-
| Position loop src | 0x2012:09 | UINT8 | 1=Enc1, 2=Enc2 |
238-
| Velocity loop src | 0x2011:05 | UINT8 | 1=Enc1, 2=Enc2 |
239-
| STO | 0x6621:01 | UINT8 | safety input |
240-
| SBC | 0x6621:02 | UINT8 | safety input |
241-
| Timestamp | 0x20F0:00 | UINT32 | µs |
242-
243-
---
244-
245-
## 11) Troubleshooting
246-
247-
* **Error:** `invalid config: encX not mounted/mapped`
248-
→ Config requested an encoder not present in PDOs. Fix XML mapping or mounts.
249-
* **Joint/motor look identical**
250-
→ Check gear ratio values; or both encoders are on same shaft.
251-
* **6064/606C look wrong**
252-
→ Verify loop source SDOs 0x2012:09 / 0x2011:05.
76+
- Unknown loop source → prefer Enc1 if mounted.
77+
- Accelerations → always `0.0`.
78+
- Safety/timestamp PDOs are handled when present.
79+
80+
## Command pipeline (overview)
81+
- Velocity mode (CSV): joint deg/s are transformed to the loop shaft and converted to rpm, then written to the velocity target. A first‑cycle latch suppresses non‑zero output.
82+
- Torque/Current mode (CST):
83+
- Torque path: joint Nm → motor Nm → per‑thousand of rated motor torque (see protocol_map.md for formulas and rated‑torque SDO).
84+
- Current path: A → motor Nm via torque constant → per‑thousand (see protocol_map.md).
85+
- On mode or CST‑flavor change, set‑points/latches are cleared to avoid stale outputs.
86+
87+
## Valid config examples
88+
1) Motor encoder only
89+
- enc1_mount=motor, enc2_mount=none
90+
- joint feedback derived from Enc1 with gear ratio inversion.
91+
92+
2) Joint encoder only
93+
- enc1_mount=none, enc2_mount=joint
94+
- motor feedback derived via gear ratio.
95+
96+
3) Dual (classical)
97+
- enc1_mount=motor, enc2_mount=joint
98+
- position_joint=enc2, position_motor=enc1
99+
- velocity_joint=606C (if vel loop source = Enc2), velocity_motor=606C or enc1.
100+
101+
4) Redundant/diagnostic
102+
- both mounted; expose 6064/606C for drive loops, plus direct enc1/enc2 for cross‑checks.
103+
104+
## Edge cases & notes
105+
- gearRatio=0 → invalid; conversions return 0.
106+
- Sign conventions must be consistent externally if mounts imply inversion.
107+
- Backlash detection (motor vs joint encoder) is out of scope.
108+
- PDO rollover is handled; always check presence before reading optional entries.
109+
110+
## Troubleshooting
111+
- Error: invalid config (encX not mounted/mapped) → Fix XML mapping or mounts.
112+
- Joint/motor look identical → Check gear ratio; or both encoders are on the same shaft.
113+
- 6064/606C look wrong → Verify loop source SDOs (indices in protocol_map.md).
114+
115+
## Related
116+
- protocol_map.md — PDO/SDO reference and unit conversions (single source of truth)
117+
- modes_and_setpoints.md — which targets are written per mode and how set‑points are cleared

0 commit comments

Comments
 (0)