YARP CiA-402 EtherCAT Device 0.6.0
YARP device plugin for EtherCAT CiA-402 drives
Loading...
Searching...
No Matches
CiA402MotionControl.cpp
Go to the documentation of this file.
1// SPDX-FileCopyrightText: Fondazione Istituto Italiano di Tecnologia (IIT)
2// SPDX-License-Identifier: BSD-3-Clause
3
6
9
10// YARP
11#include <yarp/os/LogStream.h>
12#include <yarp/os/Value.h>
13
14// STD
15#include <algorithm>
16#include <chrono>
17#include <cmath>
18#include <cstring>
19#include <memory>
20#include <mutex>
21#include <string>
22#include <string_view>
23#include <vector>
24
25namespace yarp::dev
26{
27
28/**
29 * Private implementation holding configuration, runtime state, and helpers.
30 * Concurrency:
31 * - variables.mutex guards feedback snapshots returned to YARP APIs
32 * - controlModeState.mutex guards target/active control modes
33 * - setPoints.mutex guards user setpoints and their first‑cycle latches
34 * Units:
35 * - Positions: degrees (joint and motor)
36 * - Velocities: degrees/second
37 * - Torques: joint Nm (converted to motor Nm and then to per‑thousand for PDOs)
38 */
40{
41 enum class PosSrc
42 {
43 S6064, // Use CiA 402 Position Actual Value (0x6064)
44 Enc1, // Use encoder 1 position (0x2111:02 in PDO)
45 Enc2 // Use encoder 2 position (0x2113:02 in PDO)
46 };
47 // Which object supplies velocity feedback for a given consumer (joint/motor)
48 enum class VelSrc
49 {
50 S606C, // Use CiA 402 Velocity Actual Value (0x606C) [rpm]
51 Enc1, // Use encoder 1 velocity (0x2111:03) [rpm]
52 Enc2 // Use encoder 2 velocity (0x2113:03) [rpm]
53 };
54 // Where each encoder is physically mounted relative to the gearbox
55 enum class Mount
56 {
57 None, // Not present / unknown
58 Motor, // Pre‑gearbox (motor shaft)
59 Joint // Post‑gearbox (load/joint shaft)
60 };
61 // Which sensor the drive uses internally for the closed loop
62 enum class SensorSrc
63 {
64 Unknown, // Not reported via SDOs (fallback heuristics apply)
65 Enc1, // Internal loop uses encoder 1
66 Enc2 // Internal loop uses encoder 2
67 };
68
69 // Human-readable name for log messages
70 static constexpr std::string_view kClassName = "CiA402MotionControl";
71
72 // EtherCat manager
74
75 // mutex to protect the run and the stop
77
78 // Constants (unit conversions used throughout)
79 static constexpr double MICROSECONDS_TO_SECONDS = 1e-6; // µs → s
80 // Device timestamp wraps every ~42.949672 s (spec: (2^32 - 1)/100 µs)
81 // Use +1 to account for the fractional remainder and avoid drift negative steps.
82 // 42,949,673 µs
83 static constexpr uint64_t TIMESTAMP_WRAP_PERIOD_US = (((uint64_t)1 << 32) - 1) / 100 + 1;
84 // Heuristic for wrap detection: consider a wrap only if the value is jumps backward by more
85 // than half of its range. Small backward steps can happen due to clock adjustments/resets and
86 // must not be treated as wraps.
87 static constexpr uint32_t TIMESTAMP_WRAP_HALF_RANGE = TIMESTAMP_WRAP_PERIOD_US / 2;
88 // Parameters that come from the .xml file (see open())
89 //--------------------------------------------------------------------------
90 size_t numAxes{0}; // how many joints we expose to YARP
91 int firstSlave{1}; // bus index of the first drive we care about
92 std::string expectedName{}; // sanity-check each slave.name if not empty
93
94 //--------------------------------------------------------------------------
95 // Runtime bookkeeping
96 //--------------------------------------------------------------------------
97 std::vector<double> gearRatio; // motor-revs : load-revs
99 std::vector<double> torqueConstants; // [Nm/A] from 0x2003:01
103 std::vector<uint32_t> enc1Res, enc2Res; // from 0x2110, 0x2112
105 std::vector<Mount> enc1Mount, enc2Mount; // from config (and SDO sanity)
106 std::vector<PosSrc> posSrcJoint, posSrcMotor; // from config (0x2012:08 semantics)
107 std::vector<VelSrc> velSrcJoint, velSrcMotor; // from config (0x2011:04 semantics)
108 std::vector<SensorSrc> posLoopSrc; // drive internal pos loop source (0x2012:09)
109 std::vector<SensorSrc> velLoopSrc; // drive internal vel loop source (0x2011:05)
110 std::vector<double> velToDegS; // multiply device value to get deg/s
111 std::vector<double> degSToVel; // multiply deg/s to get device value
112 std::vector<bool> invertedMotionSenseDirection; // if true the torque, current, velocity and
113 // position have inverted sign
114 struct Limits
115 {
118 std::vector<bool> usePositionLimitsFromConfig; // if false, read 0x607D from SDO and cache
119 // here
120 std::mutex mutex; // protects *all* the above vectors
122
124 {
125 mutable std::mutex mutex; // protect the variables in this structure from concurrent access
126 std::vector<double> motorEncoders; // for getMotorEncoders()
127 std::vector<double> motorVelocities; // for getMotorVelocities()
128 std::vector<double> motorAccelerations; // for getMotorAccelerations()
129 std::vector<double> jointPositions; // for getJointPositions()
130 std::vector<double> jointVelocities; // for getJointVelocities()
131 std::vector<double> jointAccelerations; // for getJointAccelerations()
132 std::vector<double> jointTorques; // for getJointTorques()
133 std::vector<double> motorCurrents; // for getCurrents()
134 std::vector<double> feedbackTime; // feedback time in seconds. Computed from
135 // drive’s own internal timestep that starts when the
136 // drive boots (or resets)
140 std::vector<bool> targetReached; // cached Statusword bit 10
141 std::vector<double> driveTemperatures; // cached drive temperature if available
142
144 {
145 this->motorEncoders.resize(numAxes);
146 this->motorVelocities.resize(numAxes);
147 this->motorAccelerations.resize(numAxes);
148 this->feedbackTime.resize(numAxes);
149 this->jointPositions.resize(numAxes);
150 this->jointVelocities.resize(numAxes);
151 this->jointAccelerations.resize(numAxes);
152 this->jointNames.resize(numAxes);
153 this->jointTorques.resize(numAxes);
154 this->motorCurrents.resize(numAxes);
155 this->STO.resize(numAxes);
156 this->SBC.resize(numAxes);
157 this->targetReached.resize(numAxes);
158 this->driveTemperatures.resize(numAxes);
159 }
160 };
161
163
165 {
166 std::vector<int> target; // what the user asked for
167 std::vector<int> active; // what the drive is really doing
168 std::vector<int> cstFlavor; // custom flavor for each axis (torque/current)
169 std::vector<int> prevCstFlavor; // previous flavor, for change detection
170 mutable std::mutex mutex; // protects *both* vectors
171
173 {
174 target.assign(n, VOCAB_CM_IDLE);
175 active = target;
176 cstFlavor.assign(n, VOCAB_CM_UNKNOWN);
178 }
179 };
181
183 {
184 std::mutex mutex; // protects the following vectors
186 std::vector<double> jointVelocities; // for velocityMove() or joint velocity commands
188 std::vector<bool> hasTorqueSP; // user provided a torque since entry?
189 std::vector<bool> hasVelSP; // user provided a velocity since entry?
190 std::vector<bool> hasCurrentSP; // user provided a current since entry?
191
192 std::vector<double> ppJointTargetsDeg; // last requested PP target [deg] joint-side
193 std::vector<int32_t> ppTargetCounts; // computed PP target for 0x607A (loop-shaft)
194 std::vector<bool> ppHasPosSP; // a new PP command available this cycle?
195 std::vector<bool> ppIsRelative; // this PP set-point is relative
196 std::vector<bool> ppPulseHi; // drive CW bit4 high this cycle?
197 std::vector<bool> ppPulseCoolDown; // bring bit4 low next
198
201
203 {
204 jointTorques.resize(n);
205 jointVelocities.resize(n);
206 motorCurrents.resize(n);
207 hasTorqueSP.assign(n, false);
208 hasVelSP.assign(n, false);
209 hasCurrentSP.assign(n, false);
210
211 ppJointTargetsDeg.resize(n);
212 ppTargetCounts.resize(n);
213 ppHasPosSP.assign(n, false);
214 ppIsRelative.assign(n, false);
215 ppPulseHi.assign(n, false);
216 ppPulseCoolDown.assign(n, false);
217
220 }
221
222 void reset()
223 {
224 std::lock_guard<std::mutex> lock(this->mutex);
225 std::fill(this->jointTorques.begin(), this->jointTorques.end(), 0.0);
226 std::fill(this->jointVelocities.begin(), this->jointVelocities.end(), 0.0);
227 std::fill(this->motorCurrents.begin(), this->motorCurrents.end(), 0.0);
228 std::fill(this->hasTorqueSP.begin(), this->hasTorqueSP.end(), false);
229 std::fill(this->hasCurrentSP.begin(), this->hasCurrentSP.end(), false);
230 std::fill(this->hasVelSP.begin(), this->hasVelSP.end(), false);
231 std::fill(this->ppJointTargetsDeg.begin(), this->ppJointTargetsDeg.end(), 0.0);
232 std::fill(this->ppTargetCounts.begin(), this->ppTargetCounts.end(), 0);
233 std::fill(this->ppHasPosSP.begin(), this->ppHasPosSP.end(), false);
234 std::fill(this->ppIsRelative.begin(), this->ppIsRelative.end(), false);
235 std::fill(this->ppPulseHi.begin(), this->ppPulseHi.end(), false);
236 std::fill(this->ppPulseCoolDown.begin(), this->ppPulseCoolDown.end(), false);
237
238 std::fill(this->positionDirectJointTargetsDeg.begin(),
239 this->positionDirectJointTargetsDeg.end(),
240 0.0);
241 std::fill(this->positionDirectTargetCounts.begin(),
242 this->positionDirectTargetCounts.end(),
243 0);
244 }
245
246 void reset(int axis)
247 {
248 std::lock_guard<std::mutex> lock(this->mutex);
249 this->jointTorques[axis] = 0.0;
250 this->jointVelocities[axis] = 0.0;
251 this->motorCurrents[axis] = 0.0;
252 this->hasTorqueSP[axis] = false;
253 this->hasCurrentSP[axis] = false;
254 this->ppJointTargetsDeg[axis] = 0.0;
255 this->ppTargetCounts[axis] = 0;
256 this->hasVelSP[axis] = false;
257 this->ppHasPosSP[axis] = false;
258 this->ppIsRelative[axis] = false;
259 this->ppPulseHi[axis] = false;
260 this->ppPulseCoolDown[axis] = false;
261 this->positionDirectJointTargetsDeg[axis] = 0.0;
262 this->positionDirectTargetCounts[axis] = 0;
263 }
264 };
265
267
268 /* --------------- CiA-402 power-state machine ------------------------ */
270
271 // First-cycle latches and seed
273 std::vector<bool> posLatched; // true if we have a valid target
276
277 // Timestamp unwrap (per-axis) for 32-bit drive timestamps
278 std::vector<uint32_t> tsLastRaw; // last raw 32-bit timestamp read from drive
279 std::vector<uint64_t> tsWraps; // number of wraps (increments on large backward jumps)
280
289
290 bool opRequested{false}; // true after the first run() call
291
292 // ------------- runtime profiling (run() duration and 5s average) -------------
293 std::chrono::steady_clock::time_point avgWindowStart{std::chrono::steady_clock::now()};
294 double runTimeAccumSec{0.0};
296
297 /** Dummy interaction mode for all the joints */
298 yarp::dev::InteractionModeEnum dummyInteractionMode{
299 yarp::dev::InteractionModeEnum::VOCAB_IM_STIFF};
300
301 Impl() = default;
302 ~Impl() = default;
303
304 // Convert joint degrees to loop-shaft counts for 0x607A, using the configured
305 // position-loop source (Enc1/Enc2) and mount (Motor/Joint).
306 int32_t jointDegToTargetCounts(size_t j, double jointDeg) const
307 {
308 // choose source and resolution
309 uint32_t res = 0;
310 Mount m = Mount::None;
311 switch (posLoopSrc[j])
312 {
313 case SensorSrc::Enc1:
314 res = enc1Res[j];
315 m = enc1Mount[j];
316 break;
317 case SensorSrc::Enc2:
318 res = enc2Res[j];
319 m = enc2Mount[j];
320 break;
321 default:
322 if (enc1Mount[j] != Mount::None)
323 {
324 res = enc1Res[j];
325 m = enc1Mount[j];
326 } else
327 {
328 res = enc2Res[j];
329 m = enc2Mount[j];
330 }
331 break;
332 }
333 double shaftDeg = jointDeg;
334 if (m == Mount::Motor)
335 shaftDeg = jointDeg * gearRatio[j];
336 else if (m == Mount::Joint)
337 shaftDeg = jointDeg; // pass-through
338 const double cnt = (res ? (shaftDeg / 360.0) * static_cast<double>(res) : 0.0);
339 long long q = llround(cnt);
344 return static_cast<int32_t>(q);
345 }
346
347 // Convert loop-shaft counts (0x607D/0x607A domain) back to joint degrees,
348 // applying encoder mount, gear ratio, and motion-sense inversion.
349 double targetCountsToJointDeg(size_t j, int32_t counts) const
350 {
351 // Apply motion-sense inversion: counts stored in the drive follow the loop shaft.
352 // If our joint coordinate is inverted, flip the sign to get a consistent mapping.
353 const bool inv = invertedMotionSenseDirection[j];
354 const int32_t cAdj = inv ? -counts : counts;
355
356 // choose source and resolution/mount just like jointDegToTargetCounts
357 uint32_t res = 0;
358 Mount m = Mount::None;
359 switch (posLoopSrc[j])
360 {
361 case SensorSrc::Enc1:
362 res = enc1Res[j];
363 m = enc1Mount[j];
364 break;
365 case SensorSrc::Enc2:
366 res = enc2Res[j];
367 m = enc2Mount[j];
368 break;
369 default:
370 if (enc1Mount[j] != Mount::None)
371 {
372 res = enc1Res[j];
373 m = enc1Mount[j];
374 } else
375 {
376 res = enc2Res[j];
377 m = enc2Mount[j];
378 }
379 break;
380 }
381
382 // counts -> shaft degrees
383 const double shaftDeg = res ? (double(cAdj) / double(res)) * 360.0 : 0.0;
384 // shaft -> joint degrees depending on mount
385 if (m == Mount::Motor)
386 {
387 return gearRatioInv[j] * shaftDeg; // joint = motor/gearRatio
388 }
389 // Joint-mounted or unknown → pass-through
390 return shaftDeg;
391 }
392
393 bool setPositionCountsLimits(int axis, int32_t minCounts, int32_t maxCounts)
394 {
395 constexpr auto logPrefix = "[setPositionCountsLimits]";
396 auto errorCode = this->ethercatManager.writeSDO<int32_t>(this->firstSlave + axis,
397 0x607D,
398 0x01,
399 minCounts);
401 {
402 yCError(CIA402,
403 "%s: setLimits: SDO write 0x607D:01 (min) failed for axis %d",
404 Impl::kClassName.data(),
405 axis);
406 return false;
407 }
408
409 errorCode = this->ethercatManager.writeSDO<int32_t>(this->firstSlave + axis,
410 0x607D,
411 0x02,
412 maxCounts);
414 {
415 yCError(CIA402,
416 "%s: setLimits: SDO write 0x607D:02 (max) failed for axis %d",
417 Impl::kClassName.data(),
418 axis);
419 return false;
420 }
421
422 return true;
423 }
424
425 //--------------------------------------------------------------------------
426 // One-shot SDO reads – here we only fetch encoder resolutions
427 //--------------------------------------------------------------------------
429 {
430 constexpr auto logPrefix = "[readEncoderResolutions]";
431
432 enc1Res.resize(numAxes);
433 enc2Res.resize(numAxes);
434 enc1ResInv.resize(numAxes);
435 enc2ResInv.resize(numAxes);
436
437 for (size_t j = 0; j < numAxes; ++j)
438 {
439 const int s = firstSlave + int(j);
440
441 uint32_t r1 = 0;
442 auto e1 = ethercatManager.readSDO<uint32_t>(s, 0x2110, 0x03, r1);
444
445 uint32_t r2 = 0;
446 auto e2 = ethercatManager.readSDO<uint32_t>(s, 0x2112, 0x03, r2);
448 }
449 for (size_t j = 0; j < numAxes; ++j)
450 {
451 enc1ResInv[j] = enc1Res[j] ? 1.0 / double(enc1Res[j]) : 0.0;
452 enc2ResInv[j] = enc2Res[j] ? 1.0 / double(enc2Res[j]) : 0.0;
453 }
454
455 // Print encoder resolution information for all axes
456 yCInfo(CIA402, "%s successfully read encoder resolutions from SDO", logPrefix);
457 for (size_t j = 0; j < numAxes; ++j)
458 {
459 yCDebug(CIA402,
460 "%s j=%zu enc1_resolution=%u (inv=%.9f), enc2_resolution=%u (inv=%.9f)",
461 logPrefix,
462 j,
463 enc1Res[j],
464 enc1ResInv[j],
465 enc2Res[j],
466 enc2ResInv[j]);
467 }
468
469 return true;
470 }
471
473 {
474 // Known Synapticon encodings (prefix scales; middle bytes encode rev, last timebase)
475 // RPM family
476 if (v == 0x00B44700u)
477 return {6.0, 1.0 / 6.0, "1 RPM"}; // 1 rpm -> 6 deg/s
478 if (v == 0xFFB44700u)
479 return {0.6, 1.0 / 0.6, "0.1 RPM"};
480 if (v == 0xFEB44700u)
481 return {0.06, 1.0 / 0.06, "0.01 RPM"};
482 if (v == 0xFDB44700u)
483 return {0.006, 1.0 / 0.006, "0.001 RPM"};
484 // RPS family
485 if (v == 0x00B40300u)
486 return {360.0, 1.0 / 360.0, "1 RPS"};
487 if (v == 0xFFB40300u)
488 return {36.0, 1.0 / 36.0, "0.1 RPS"};
489 if (v == 0xFEB40300u)
490 return {3.6, 1.0 / 3.6, "0.01 RPS"};
491 if (v == 0xFDB40300u)
492 return {0.36, 1.0 / 0.36, "0.001 RPS"};
493
494 // Fallback (spec says default is 1 RPM). Warn & assume 1 RPM.
495 return {6.0, 1.0 / 6.0, "UNKNOWN (assume 1 RPM)"};
496 }
497
499 {
500 constexpr auto logPrefix = "[readSiVelocityUnits]";
501
502 this->velToDegS.resize(numAxes);
503 this->degSToVel.resize(numAxes);
504
505 for (size_t j = 0; j < numAxes; ++j)
506 {
507 const int s = firstSlave + int(j);
508 // default 1 RPM See
509 // https://doc.synapticon.com/circulo/sw5.1/objects_html/6xxx/60a9.html?Highlight=0x60a9
510 uint32_t raw = 0x00B44700u;
511 auto e = ethercatManager.readSDO<uint32_t>(s, 0x60A9, 0x00, raw);
512
513 auto [toDegS, toDev, name] = this->decode60A9(raw);
514 velToDegS[j] = toDegS;
515 degSToVel[j] = toDev;
516
518 yCDebug(CIA402,
519 "%s j=%zu 0x60A9=0x%08X velocity_unit=%s (1_unit=%.6f_deg/s)",
520 logPrefix,
521 j,
522 raw,
523 name,
524 toDegS);
525 else
526 yWarning("%s j=%zu failed to read 0x60A9, assuming 1_RPM (1_unit=6_deg/s)",
527 logPrefix,
528 j);
529 }
530
531 yCInfo(CIA402, "%s successfully read velocity conversion units from SDO", logPrefix);
532 return true;
533 }
534
535 // Convert loop-shaft counts to joint degrees, using the configured
536 double loopCountsToJointDeg(std::size_t j, double counts) const
537 {
538 // Pick loop sensor & mount (we already filled posLoopSrc[] in open())
539 uint32_t res = 0;
540 Mount mount = Mount::None;
541 switch (posLoopSrc[j])
542 {
543 case SensorSrc::Enc1:
544 res = enc1Res[j];
545 mount = enc1Mount[j];
546 break;
547 case SensorSrc::Enc2:
548 res = enc2Res[j];
549 mount = enc2Mount[j];
550 break;
551 default: // fallback: prefer enc1 if available
552 if (enc1Mount[j] != Mount::None && enc1Res[j] != 0)
553 {
554 res = enc1Res[j];
555 mount = enc1Mount[j];
556 } else
557 {
558 res = enc2Res[j];
559 mount = enc2Mount[j];
560 }
561 break;
562 }
563 if (res == 0 || mount == Mount::None)
564 return 0.0; // no info
565
566 const double shaftDeg = (counts / double(res)) * 360.0; // degrees on the measured shaft
567 // Convert to JOINT side depending on mount
568
569 yCDebug(CIA402,
570 "loopCountsToJointDeg j=%zu counts=%.3f res=%u mount=%d -> shaftDeg=%.9f",
571 j,
572 counts,
573 res,
574 static_cast<int>(mount),
575 shaftDeg);
576
577 if (mount == Mount::Motor)
578 return shaftDeg * gearRatioInv[j]; // motor → joint
579 /* mount == Mount::Joint */ return shaftDeg; // already joint
580 }
581
582 bool setPositionWindowDeg(int j, double winDeg, double winTime_ms)
583 {
584 if (j < 0 || j >= static_cast<int>(this->numAxes))
585 {
586 yCError(CIA402,
587 "%s: setPositionWindowDeg: invalid joint index",
588 Impl::kClassName.data());
589 return false;
590 }
591 const int s = this->firstSlave + j;
592
593 uint32_t rawWin = 0;
594 if (std::isinf(winDeg))
595 {
596 // Per doc: monitoring OFF → target reached bit stays 0.
597 rawWin = 0xFFFFFFFFu;
598 } else
599 {
600 rawWin = static_cast<uint32_t>(
601 std::round(std::abs(this->jointDegToTargetCounts(std::size_t(j), winDeg))));
602 }
603 uint32_t rawTime = static_cast<uint32_t>(std::round(std::max(0.0, winTime_ms)));
604
605 auto e1 = this->ethercatManager.writeSDO<uint32_t>(s, 0x6067, 0x00, rawWin);
607 {
608 yCError(CIA402,
609 "%s: setPositionWindowDeg: SDO 0x6067 write failed on joint %d",
610 Impl::kClassName.data(),
611 j);
612 return false;
613 }
614 auto e2 = this->ethercatManager.writeSDO<uint32_t>(s, 0x6068, 0x00, rawTime);
616 {
617 yCError(CIA402,
618 "%s: setPositionWindowDeg: SDO 0x6068 write failed on joint %d",
619 Impl::kClassName.data(),
620 j);
621 return false;
622 }
623 return true;
624 }
625
626 bool getPositionControlStrategy(uint16_t& strategyValue)
627 {
628 constexpr auto logPrefix = "[getPositionControlStrategy]";
629
630 // Read from first axis only (all should be the same)
631 const int slaveIdx = firstSlave;
632 const auto err
633 = ethercatManager.readSDO<uint16_t>(slaveIdx, 0x2002, 0x00, strategyValue);
635 {
636 yCError(CIA402,
637 "%s failed to read 0x2002:00",
638 logPrefix);
639 return false;
640 }
641
642 yCInfo(CIA402,
643 "%s read position strategy %u from first axis",
644 logPrefix,
645 static_cast<unsigned>(strategyValue));
646 return true;
647 }
648
649 bool setPositionControlStrategy(uint16_t strategyValue)
650 {
651 constexpr auto logPrefix = "[setPositionControlStrategy]";
652
653 for (size_t j = 0; j < numAxes; ++j)
654 {
655 const int slaveIdx = firstSlave + static_cast<int>(j);
656 const auto err
657 = ethercatManager.writeSDO<uint16_t>(slaveIdx, 0x2002, 0x00, strategyValue);
659 {
660 yCError(CIA402,
661 "%s j=%zu failed to set 0x2002:00 (value=%u)",
662 logPrefix,
663 j,
664 static_cast<unsigned>(strategyValue));
665 return false;
666 }
667 }
668
669 yCInfo(CIA402,
670 "%s configured %zu axes with position strategy %u",
671 logPrefix,
672 numAxes,
673 static_cast<unsigned>(strategyValue));
674 return true;
675 }
676
677
679 std::vector<double>& kdNmSecPerDeg)
680 {
681 constexpr auto logPrefix = "[readSimplePidGains]";
682
683 kpNmPerDeg.resize(numAxes);
684 kdNmSecPerDeg.resize(numAxes);
685
686 for (size_t j = 0; j < numAxes; ++j)
687 {
688 const int slaveIdx = firstSlave + static_cast<int>(j);
689 float32 kpValue = 0.0f;
690 float32 kdValue = 0.0f;
691
692 const auto errKp = ethercatManager.readSDO<float32>(slaveIdx, 0x2012, 0x01, kpValue);
693 const auto errKd = ethercatManager.readSDO<float32>(slaveIdx, 0x2012, 0x03, kdValue);
694
697 {
698 yCError(CIA402,
699 "%s j=%zu failed to read gains (errs=%d,%d)",
700 logPrefix,
701 j,
702 static_cast<int>(errKp),
703 static_cast<int>(errKd));
704 return false;
705 }
706
707 const double degPerCount = loopCountsToJointDeg(j, 1.0);
708 const double kpMotor_mNm_per_deg = static_cast<double>(kpValue) / degPerCount;
709 const double kdMotor_mNmS_per_deg = static_cast<double>(kdValue) / degPerCount;
710
711 kpNmPerDeg[j] = (kpMotor_mNm_per_deg * gearRatio[j]) / 1000.0;
712 kdNmSecPerDeg[j] = (kdMotor_mNmS_per_deg * gearRatio[j]) / 1000.0;
713
714 yCDebug(CIA402,
715 "%s j=%zu read gains: kp_device=%.3f[mNm/inc], kd_device=%.3f[mNm*s/inc] "
716 "=> kp_motor=%.6f[mNm/deg], kd_motor=%.6f[mNm*s/deg] => "
717 "kp_joint=%.6f[Nm/deg], kd_joint=%.6f[Nm*s/deg]",
718 logPrefix,
719 j,
720 kpValue,
721 kdValue,
722 kpMotor_mNm_per_deg,
723 kdMotor_mNmS_per_deg,
724 kpNmPerDeg[j],
725 kdNmSecPerDeg[j]);
726 }
727 yCInfo(CIA402, "%s read simple PID gains for %zu axes", logPrefix, numAxes);
728 return true;
729 }
730
732 const std::vector<double>& kdNmSecPerDeg)
733 {
734 constexpr auto logPrefix = "[configureSimplePidGains]";
735
736 if (kpNmPerDeg.size() != numAxes || kdNmSecPerDeg.size() != numAxes)
737 {
738 yCError(CIA402,
739 "%s mismatched gain vector sizes (kp=%zu kd=%zu expected=%zu)",
740 logPrefix,
741 kpNmPerDeg.size(),
742 kdNmSecPerDeg.size(),
743 numAxes);
744 return false;
745 }
746
747 for (size_t j = 0; j < numAxes; ++j)
748 {
749 if (gearRatio[j] == 0.0)
750 {
751 yCError(CIA402, "%s j=%zu invalid gear ratio (0)", logPrefix, j);
752 return false;
753 }
754
755 const double degPerCount = loopCountsToJointDeg(j, 1.0);
756 if (degPerCount == 0.0)
757 {
758 yCError(CIA402,
759 "%s j=%zu cannot derive counts/deg (loop source missing)",
760 logPrefix,
761 j);
762 return false;
763 }
764 const double kpMotor_mNm_per_deg = (kpNmPerDeg[j] / gearRatio[j]) * 1000.0;
765 const double kdMotor_mNmS_per_deg = (kdNmSecPerDeg[j] / gearRatio[j]) * 1000.0;
766
767 const double kpDevice = kpMotor_mNm_per_deg * degPerCount;
768 const double kdDevice = kdMotor_mNmS_per_deg * degPerCount;
769
770 const float32 kpValue = static_cast<float32>(kpDevice);
771 const float32 kdValue = static_cast<float32>(kdDevice);
772 constexpr float32 kiValue = 0.0f;
773
774
775 yCDebug(CIA402,
776 "%s j=%zu computing gains: kp_joint=%.6f[Nm/deg], kd_joint=%.6f[Nm*s/deg], "
777 "gearRatio=%.6f, degPerCount=%.9f => kp_motor=%.6f[mNm/deg], "
778 "kd_motor=%.6f[mNm*s/deg] => kp_device=%.3f[mNm/inc], kd_device=%.3f[mNm*s/inc]",
779 logPrefix,
780 j,
781 kpNmPerDeg[j],
782 kdNmSecPerDeg[j],
783 gearRatio[j],
784 degPerCount,
785 kpMotor_mNm_per_deg,
786 kdMotor_mNmS_per_deg,
787 kpDevice,
788 kdDevice);
789
790 const int slaveIdx = firstSlave + static_cast<int>(j);
791 const auto errKp = ethercatManager.writeSDO<float32>(slaveIdx, 0x2012, 0x01, kpValue);
792 const auto errKi = ethercatManager.writeSDO<float32>(slaveIdx, 0x2012, 0x02, kiValue);
793 const auto errKd = ethercatManager.writeSDO<float32>(slaveIdx, 0x2012, 0x03, kdValue);
794
798 {
799 yCError(CIA402,
800 "%s j=%zu failed to program gains (errs=%d,%d,%d). Gains "
801 "Kp=%.3f[mNm/inc]=%.3f[Nm/deg], Kd=%.3f[mNm*s/inc]=%.3f[Nm*s/deg]",
802 logPrefix,
803 j,
804 static_cast<int>(errKp),
805 static_cast<int>(errKi),
806 static_cast<int>(errKd),
807 kpValue,
808 kpNmPerDeg[j],
809 kdValue,
810 kdNmSecPerDeg[j]);
811 return false;
812 }
813
814 yCDebug(CIA402,
815 "%s j=%zu Kp=%.3f[mNm/inc] Kd=%.3f[mNm*s/inc]",
816 logPrefix,
817 j,
818 kpValue,
819 kdValue);
820 }
821
822 yCInfo(CIA402, "%s programmed simple PID gains for %zu axes", logPrefix, numAxes);
823 return true;
824 }
825
827 {
828 constexpr auto logPrefix = "[readMotorConstants]";
829
830 torqueConstants.resize(numAxes);
831 maxCurrentsA.resize(numAxes);
832
833 for (size_t j = 0; j < numAxes; ++j)
834 {
835 const int s = firstSlave + int(j);
836 int32_t tcMicroNmA = 0;
837 if (ethercatManager.readSDO<int32_t>(s, 0x2003, 0x02, tcMicroNmA)
839 || tcMicroNmA == 0)
840 {
841 yWarning("%s j=%zu cannot read torque constant (0x2003:02) or zero, assuming 1.0 "
842 "Nm/A",
843 logPrefix,
844 j);
845 torqueConstants[j] = 1.0;
846 } else
847 {
848 // convert from µNm/A to Nm/A
849 torqueConstants[j] = double(tcMicroNmA) * 1e-6;
850 }
851
852 // first of all we need to read the motor rated current
853 // 0x6075:00 Motor Rated Current (UNSIGNED32)
854 uint32_t ratedCurrentMilliA = 0;
855 double ratedCurrentA = 0.0;
856 if (ethercatManager.readSDO<uint32_t>(s, 0x6075, 0x00, ratedCurrentMilliA)
858 || ratedCurrentMilliA == 0)
859 {
860 yWarning("%s j=%zu cannot read motor rated current (0x6075:00) or zero, assuming "
861 "1.0 A",
862 logPrefix,
863 j);
864 ratedCurrentA = 1.0;
865 } else
866 {
867 // convert from mA to A
868 ratedCurrentA = double(ratedCurrentMilliA) * 1e-3;
869 }
870
871 // Now we can read the max current 0x6073:0 16 bit unsigned
872 uint16_t maxPermille = 0;
873 if (ethercatManager.readSDO<uint16_t>(s, 0x6073, 0x00, maxPermille)
875 {
876 yWarning("%s j=%zu cannot read max current (0x6073:00), assuming 1000 per_mille",
877 logPrefix,
878 j);
879 maxPermille = 1000;
880 }
881
882 yCDebug(CIA402,
883 "%s j=%zu max_current=%u_permille (%.3fA), torque_constant=%.6f_Nm/A",
884 logPrefix,
885 j,
886 maxPermille,
887 (double(maxPermille) / 1000.0) * ratedCurrentA,
888 this->torqueConstants[j]);
889
890 maxCurrentsA[j] = (double(maxPermille) / 1000.0) * ratedCurrentA;
891 }
892
893 yCInfo(CIA402, "%s successfully read motor constants from SDO", logPrefix);
894 return true;
895 }
896
897 /**
898 * Read the gear-ratio (motor-revs : load-revs) for every axis and cache both
899 * the ratio and its inverse.
900 *
901 * 0x6091:01 numerator (UNSIGNED32, default 1)
902 * 0x6091:02 denominator (UNSIGNED32, default 1)
903 *
904 * If the object is missing or invalid the code silently falls back to 1:1.
905 */
907 {
908 constexpr auto logPrefix = "[readGearRatios]";
909
910 gearRatio.resize(numAxes);
911 gearRatioInv.resize(numAxes);
912
913 for (size_t j = 0; j < numAxes; ++j)
914 {
915 const int slaveIdx = firstSlave + static_cast<int>(j);
916
917 uint32_t num = 1U; // default numerator
918 uint32_t den = 1U; // default denominator
919
920 // ---- numerator ------------------------------------------------------
921 if (ethercatManager.readSDO<uint32_t>(slaveIdx, 0x6091, 0x01, num)
923 {
924 yWarning("%s j=%zu gear_ratio_numerator not available (0x6091:01), assuming 1",
925 logPrefix,
926 j);
927 num = 1U;
928 }
929
930 // ---- denominator ----------------------------------------------------
931 if (ethercatManager.readSDO<uint32_t>(slaveIdx, 0x6091, 0x02, den)
933 || den == 0U)
934 {
935 yWarning("%s j=%zu gear_ratio_denominator not available/zero (0x6091:02), assuming "
936 "1",
937 logPrefix,
938 j);
939 den = 1U;
940 }
941
942 yCDebug(CIA402,
943 "%s j=%zu gear_ratio=%u:%u (ratio=%.6f)",
944 logPrefix,
945 j,
946 num,
947 den,
948 static_cast<double>(num) / static_cast<double>(den));
949
950 // ---- cache value ----------------------------------------------------
951 gearRatio[j] = static_cast<double>(num) / static_cast<double>(den);
952 }
953
954 // Pre‑compute the inverse for fast use elsewhere -------------------------
955 for (size_t j = 0; j < numAxes; ++j)
956 {
957 gearRatioInv[j] = (gearRatio[j] != 0.0) ? (1.0 / gearRatio[j]) : 0.0;
958 }
959
960 yCInfo(CIA402, "%s successfully read gear ratios from SDO", logPrefix);
961 return true;
962 }
963
965 {
966 constexpr auto logPrefix = "[readTorqueValues]";
967
970
971 for (size_t j = 0; j < numAxes; ++j)
972 {
973 const int s = firstSlave + int(j);
974 uint32_t rated_mNm = 0;
975 if (ethercatManager.readSDO<uint32_t>(s, 0x6076, 0x00, rated_mNm)
977 {
978 yCError(CIA402, "%s j=%zu cannot read rated torque (0x6076:00)", logPrefix, j);
979 return false;
980 }
981 ratedMotorTorqueNm[j] = double(rated_mNm) / 1000.0; // motor Nm
982 }
983 for (size_t j = 0; j < numAxes; ++j)
984 {
985 const int s = firstSlave + int(j);
986 uint16_t maxPerm = 0;
987 if (ethercatManager.readSDO<uint16_t>(s, 0x6072, 0x00, maxPerm)
989 {
990 yCError(CIA402, "%s j=%zu cannot read max torque (0x6072:00)", logPrefix, j);
991 return false;
992 }
993 maxMotorTorqueNm[j] = (double(maxPerm) / 1000.0) * ratedMotorTorqueNm[j];
994 yCDebug(CIA402,
995 "%s j=%zu motor_rated_torque=%.3fNm max_torque=%.3fNm",
996 logPrefix,
997 j,
1000 }
1001
1002 yCInfo(CIA402, "%s successfully read torque values from SDO", logPrefix);
1003 return true;
1004 }
1005
1006 void setSDORefSpeed(int j, double spDegS)
1007 {
1008 // ---- map JOINT deg/s -> LOOP SHAFT deg/s (based on pos loop source + mount) ----
1009 double shaft_deg_s = spDegS; // default assume joint shaft
1010 switch (this->posLoopSrc[j])
1011 {
1013 if (this->enc1Mount[j] == Impl::Mount::Motor)
1014 shaft_deg_s = spDegS * this->gearRatio[j];
1015 else if (this->enc1Mount[j] == Impl::Mount::Joint)
1016 shaft_deg_s = spDegS;
1017 break;
1019 if (this->enc2Mount[j] == Impl::Mount::Motor)
1020 shaft_deg_s = spDegS * this->gearRatio[j];
1021 else if (this->enc2Mount[j] == Impl::Mount::Joint)
1022 shaft_deg_s = spDegS;
1023 break;
1025 default:
1026 // Fallback: if we know which encoder is motor-mounted, assume that one; otherwise leave
1027 // as joint.
1028 if (this->enc1Mount[j] == Impl::Mount::Motor
1029 || this->enc2Mount[j] == Impl::Mount::Motor)
1030 shaft_deg_s = spDegS * this->gearRatio[j];
1031 break;
1032 }
1033
1034 // Convert deg/s on the loop shaft -> device velocity units using 0x60A9
1035 const int s = this->firstSlave + j;
1036 const int32_t vel = static_cast<int32_t>(std::llround(shaft_deg_s * this->degSToVel[j]));
1037 (void)this->ethercatManager.writeSDO<int32_t>(s, 0x6081, 0x00, vel);
1038 }
1039
1041 {
1042 std::lock_guard<std::mutex> lock(this->setPoints.mutex);
1043
1044 /**
1045 * Push user setpoints into RxPDOs according to the active control mode.
1046 * - Torque (CST): joint Nm → motor Nm → per‑thousand of rated motor torque (0x6071)
1047 * - Velocity (CSV): joint deg/s → loop‑shaft deg/s (mount aware) → rpm (0x60FF)
1048 * First‑cycle latches (velLatched/trqLatched) zero the command once when entering.
1049 */
1050 for (size_t j = 0; j < this->numAxes; ++j)
1051 {
1052 const int s = firstSlave + int(j);
1053 auto rx = this->ethercatManager.getRxPDO(s);
1054 const int opMode = this->controlModeState.active[j];
1055
1056 // clean rx targets
1057 rx->TargetPosition = 0;
1058 rx->TargetTorque = 0;
1059 rx->TargetVelocity = 0;
1060
1061 // ---------- TORQUE (CST) ----------
1062 if (opMode == VOCAB_CM_TORQUE)
1063 {
1064 if (!this->trqLatched[j])
1065 {
1066 rx->TargetTorque = 0;
1067 this->trqLatched[j] = true;
1068 } else
1069 {
1070 // YARP gives joint torque [Nm] → convert to MOTOR torque before 0x6071
1071 const double jointNm = setPoints.hasTorqueSP[j] ? setPoints.jointTorques[j]
1072 : 0.0;
1073 const double motorNm = (gearRatio[j] != 0.0) ? (jointNm / gearRatio[j]) : 0.0;
1074
1075 // 0x6071 is per-thousand of rated MOTOR torque (0x6076 in Nm)
1076 const int16_t tq_thousand = static_cast<int16_t>(std::llround(
1077 (ratedMotorTorqueNm[j] != 0.0 ? motorNm / ratedMotorTorqueNm[j] : 0.0)
1078 * 1000.0));
1079 rx->TargetTorque = this->invertedMotionSenseDirection[j] ? -tq_thousand
1080 : tq_thousand;
1081 }
1082 }
1083
1084 // ---------- VELOCITY (CSV) ----------
1085 if (opMode == VOCAB_CM_VELOCITY)
1086 {
1087 if (!velLatched[j])
1088 {
1089 rx->TargetVelocity = 0;
1090 velLatched[j] = true;
1091 } else
1092 {
1093 // YARP gives JOINT-side velocity [deg/s]
1094 const double joint_deg_s = setPoints.hasVelSP[j] ? setPoints.jointVelocities[j]
1095 : 0.0;
1096
1097 // Command must be on the SHAFT used by the velocity loop:
1098 // - if loop sensor is motor-mounted → convert joint→motor (× gearRatio)
1099 // - if loop sensor is joint-mounted → pass through
1100 double shaft_deg_s = joint_deg_s; // default: joint shaft
1101
1102 // The desired velocity setpoint depends on which encoder is used for
1103 // the position loop and how it is mounted.
1104 switch (posLoopSrc[j])
1105 {
1107 if (enc1Mount[j] == Impl::Mount::Motor)
1108 shaft_deg_s = joint_deg_s * gearRatio[j];
1109 else if (enc1Mount[j] == Impl::Mount::Joint)
1110 shaft_deg_s = joint_deg_s;
1111 // Impl::Mount::None → leave default (best-effort)
1112 break;
1113
1115 if (enc2Mount[j] == Impl::Mount::Motor)
1116 shaft_deg_s = joint_deg_s * gearRatio[j];
1117 else if (enc2Mount[j] == Impl::Mount::Joint)
1118 shaft_deg_s = joint_deg_s;
1119 break;
1120
1122 default:
1123 // Heuristic fallback: if we *know* the configured velocity feedback
1124 // is motor-mounted, assume motor shaft; otherwise joint shaft.
1125 // (Leave as joint if you don't keep velSrc vectors here.)
1126 break;
1127 }
1128
1129 // Convert deg/s → native velocity on the selected shaft for 0x60FF
1130 const double vel = shaft_deg_s * this->degSToVel[j];
1131 rx->TargetVelocity = static_cast<int32_t>(std::llround(vel))
1132 * (this->invertedMotionSenseDirection[j] ? -1 : 1);
1133 }
1134 }
1135
1136 // ---------- POSITION (PP) ----------
1137 if (opMode == VOCAB_CM_POSITION)
1138 {
1139
1140 if (this->ppState.ppHaltRequested[j])
1141 rx->Controlword |= (1u << 8);
1142 else
1143 rx->Controlword &= ~(1u << 8);
1144 // latch on first cycle in PP → do nothing until a user set-point arrives
1145 if (!posLatched[j])
1146 {
1147 // keep bit 5 asserted in PP (single-set-point method)
1148 rx->Controlword |= (1u << 5); // Change set immediately
1149 rx->Controlword &= ~(1u << 4); // make sure New set-point is low first
1150 posLatched[j] = true;
1151
1152 // compute seed from current measured joint angle
1153 const double currentJointDeg = this->variables.jointPositions[j];
1154 const int32_t seedStoreCounts
1155 = this->jointDegToTargetCounts(j, currentJointDeg);
1156
1157 // If the user already queued a PP target before the first cycle in PP, do
1158 // not overwrite it with the seed; otherwise seed the cached target with the
1159 // current position so the drive starts from a consistent reference.
1160 if (!setPoints.ppHasPosSP[j])
1161 {
1162 setPoints.ppTargetCounts[j] = seedStoreCounts;
1163 setPoints.ppJointTargetsDeg[j] = currentJointDeg;
1164 setPoints.ppIsRelative[j] = false;
1165 }
1166
1167 // Populate 0x607A with the cached target (seeded or user provided). The
1168 // rising edge on bit4 will be generated in the next cycle.
1169 const int32_t driveTargetCounts = this->invertedMotionSenseDirection[j]
1170 ? -setPoints.ppTargetCounts[j]
1171 : setPoints.ppTargetCounts[j];
1172 rx->TargetPosition = driveTargetCounts;
1173
1174 // If no user set-point was pending, schedule a one-shot bit4 pulse to align
1175 // the drive target to the current position.
1176 if (!setPoints.ppHasPosSP[j] && !setPoints.ppPulseHi[j])
1177 {
1178 setPoints.ppPulseHi[j] = true; // sync drive target to current position
1179 }
1180 } else
1181 {
1182 // (A) Always assert bit 5 in PP
1183 rx->Controlword |= (1u << 5);
1184
1185 // (B) If the previous cycle drove bit4 high, bring it low now (one-shot pulse)
1186 if (setPoints.ppPulseCoolDown[j])
1187 {
1188 rx->Controlword &= ~(1u << 4);
1189 setPoints.ppPulseCoolDown[j] = false;
1190 }
1191
1192 // (C) New set-point pending? write 0x607A and raise bit4
1193 int32_t targetPositionCounts = 0;
1194 if (setPoints.ppHasPosSP[j] || setPoints.ppPulseHi[j])
1195 {
1196 // Absolute/Relative selection (CW bit 6)
1197 if (setPoints.ppIsRelative[j])
1198 rx->Controlword |= (1u << 6);
1199 else
1200 rx->Controlword &= ~(1u << 6);
1201
1202 // Target position (0x607A)
1203 targetPositionCounts = this->invertedMotionSenseDirection[j]
1204 ? -setPoints.ppTargetCounts[j]
1205 : setPoints.ppTargetCounts[j];
1206
1207 // New set-point pulse (rising edge)
1208 rx->Controlword |= (1u << 4);
1209
1210 // consume the request and arm cooldown to drop bit4 next cycle
1211 setPoints.ppHasPosSP[j] = false;
1212 setPoints.ppPulseHi[j] = false;
1213 setPoints.ppPulseCoolDown[j] = true;
1214 } else
1215 {
1216 auto tx = this->ethercatManager.getTxView(s);
1217 targetPositionCounts = this->invertedMotionSenseDirection[j]
1218 ? -setPoints.ppTargetCounts[j]
1219 : setPoints.ppTargetCounts[j];
1221 {
1222 targetPositionCounts = tx.get<int32_t>(CiA402::TxField::Position6064,
1223 targetPositionCounts);
1224 }
1225
1226 setPoints.ppTargetCounts[j] = this->invertedMotionSenseDirection[j]
1227 ? -targetPositionCounts
1228 : targetPositionCounts;
1229 setPoints.ppJointTargetsDeg[j]
1230 = this->targetCountsToJointDeg(j, targetPositionCounts);
1231 setPoints.ppIsRelative[j] = false;
1232 }
1233
1234 rx->TargetPosition = targetPositionCounts;
1235 }
1236 }
1237
1238 // ---------- POSITION DIRECT (CSP) ----------
1239 if (opMode == VOCAB_CM_POSITION_DIRECT)
1240 {
1241 if (!posLatched[j])
1242 {
1243 const double currentJointDeg = this->variables.jointPositions[j];
1244 const int32_t seedCounts = this->jointDegToTargetCounts(j, currentJointDeg);
1245 setPoints.positionDirectJointTargetsDeg[j] = currentJointDeg;
1246 setPoints.positionDirectTargetCounts[j] = seedCounts;
1247 posLatched[j] = true;
1248 }
1249
1250 const int32_t driveCounts = this->invertedMotionSenseDirection[j]
1251 ? -setPoints.positionDirectTargetCounts[j]
1252 : setPoints.positionDirectTargetCounts[j];
1253 rx->TargetPosition = driveCounts;
1254 }
1255
1256 if (opMode == VOCAB_CM_CURRENT)
1257 {
1258 if (!this->currLatched[j])
1259 {
1260 // the current control is actually a torque control
1261 rx->TargetTorque = 0;
1262 this->currLatched[j] = true;
1263 } else
1264 {
1265 // YARP gives Currents [A] → convert to MOTOR torque before 0x6071
1266 const double currentA = setPoints.hasCurrentSP[j] ? setPoints.motorCurrents[j]
1267 : 0.0;
1268
1269 // convert the current in torque using the torque constant
1270 const double torqueNm = currentA * this->torqueConstants[j];
1271
1272 // 0x6071 is per-thousand of rated MOTOR torque (0x6076 in Nm)
1273 const int16_t tq_thousand = static_cast<int16_t>(std::llround(
1274 (ratedMotorTorqueNm[j] != 0.0 ? torqueNm / ratedMotorTorqueNm[j] : 0.0)
1275 * 1000.0));
1276 rx->TargetTorque = this->invertedMotionSenseDirection[j] ? -tq_thousand
1277 : tq_thousand;
1278 }
1279 }
1280 }
1281 return true;
1282 }
1283
1285 {
1286 std::lock_guard<std::mutex> lock(this->variables.mutex);
1287
1288 // =====================================================================
1289 // SHAFT TRANSFORMATION HELPERS
1290 // =====================================================================
1291 // These lambdas handle the complex coordinate transformations between
1292 // motor shaft and joint/load shaft based on encoder mounting and gear ratios
1293
1294 // Position transformation: converts degrees on a specific shaft to the requested side
1295 auto shaftFromMount_pos = [&](double deg, Mount m, size_t j, bool asMotor) -> double {
1296 // deg = input position in degrees on the physical shaft of mount 'm'
1297 // asMotor = true if we want result on motor shaft, false for joint shaft
1298
1299 if (m == Impl::Mount::Motor)
1300 {
1301 // Input is on motor shaft
1302 return asMotor ? deg // Motor->Motor: no change
1303 : deg * gearRatioInv[j]; // Motor->Joint: divide by gear ratio
1304 }
1305 if (m == Impl::Mount::Joint)
1306 {
1307 // Input is on joint/load shaft
1308 return asMotor ? deg * gearRatio[j] // Joint->Motor: multiply by gear ratio
1309 : deg; // Joint->Joint: no change
1310 }
1311 return 0.0; // Impl::Mount::None or invalid
1312 };
1313
1314 // Velocity transformation: same logic as position but for velocities
1315 auto shaftFromMount_vel = [&](double degs, Mount m, size_t j, bool asMotor) -> double {
1316 if (m == Impl::Mount::Motor)
1317 {
1318 return asMotor ? degs : degs * gearRatioInv[j];
1319 }
1320 if (m == Impl::Mount::Joint)
1321 {
1322 return asMotor ? degs * gearRatio[j] : degs;
1323 }
1324 return 0.0;
1325 };
1326
1327 for (size_t j = 0; j < this->numAxes; ++j)
1328 {
1329 const int s = this->firstSlave + int(j);
1330 auto tx = this->ethercatManager.getTxView(s);
1331
1332 // =====================================================================
1333 // Status word bits
1334 // =====================================================================
1335 const uint16_t sw = tx.get<uint16_t>(CiA402::TxField::Statusword);
1336 this->variables.targetReached[j] = (sw & (1u << 10)) != 0;
1337
1338 // =====================================================================
1339 // RAW DATA EXTRACTION FROM PDOs
1340 // =====================================================================
1341 // Read raw encoder counts and velocities from the EtherCAT PDOs
1342 // These are the fundamental data sources before any interpretation
1343
1344 // Position data (in encoder counts)
1345 const int32_t p6064 = tx.get<int32_t>(CiA402::TxField::Position6064, 0); // CiA402
1346 // standard
1347 // position
1348 const int32_t pE1 = tx.has(CiA402::TxField::Enc1Pos2111_02) // Encoder 1 position (if
1349 // mapped)
1350 ? tx.get<int32_t>(CiA402::TxField::Enc1Pos2111_02)
1351 : 0;
1352 const int32_t pE2 = tx.has(CiA402::TxField::Enc2Pos2113_02) // Encoder 2 position (if
1353 // mapped)
1354 ? tx.get<int32_t>(CiA402::TxField::Enc2Pos2113_02)
1355 : 0;
1356
1357 // Velocity data (in RPM for CiA402, encoder-specific units for others)
1358 const int32_t v606C = tx.get<int32_t>(CiA402::TxField::Velocity606C, 0); // CiA402
1359 // standard
1360 // velocity
1361 // (RPM)
1362 const int32_t vE1 = tx.has(CiA402::TxField::Enc1Vel2111_03) // Encoder 1 velocity (if
1363 // mapped)
1364 ? tx.get<int32_t>(CiA402::TxField::Enc1Vel2111_03)
1365 : 0;
1366 const int32_t vE2 = tx.has(CiA402::TxField::Enc2Vel2113_03) // Encoder 2 velocity (if
1367 // mapped)
1368 ? tx.get<int32_t>(CiA402::TxField::Enc2Vel2113_03)
1369 : 0;
1370
1371 // =====================================================================
1372 // SOURCE INTERPRETATION HELPERS
1373 // =====================================================================
1374 // These lambdas convert raw data to degrees on the encoder's own shaft,
1375 // taking into account encoder resolution and the mounting location
1376
1377 // Convert position source to degrees on its own physical shaft
1378 auto posDegOnOwnShaft = [&](PosSrc s) -> std::pair<double, Mount> {
1379 switch (s)
1380 {
1381 case Impl::PosSrc::Enc1:
1382 // Direct encoder 1 readout: counts -> degrees using enc1 resolution
1383 return {double(pE1) * enc1ResInv[j] * 360.0, enc1Mount[j]};
1384
1385 case Impl::PosSrc::Enc2:
1386 // Direct encoder 2 readout: counts -> degrees using enc2 resolution
1387 return {double(pE2) * enc2ResInv[j] * 360.0, enc2Mount[j]};
1388
1390 default: {
1391 // CiA402 standard object - interpretation depends on drive's loop source
1392 // The drive tells us which encoder it uses internally via posLoopSrc
1393 if (posLoopSrc[j] == Impl::SensorSrc::Enc1 && enc1ResInv[j] != 0.0)
1394 return {double(p6064) * enc1ResInv[j] * 360.0, enc1Mount[j]};
1395 if (posLoopSrc[j] == Impl::SensorSrc::Enc2 && enc2ResInv[j] != 0.0)
1396 return {double(p6064) * enc2ResInv[j] * 360.0, enc2Mount[j]};
1397
1398 // Fallback: if loop source unknown, prefer enc1 if available
1399 if (enc1Mount[j] != Impl::Mount::None && enc1ResInv[j] != 0.0)
1400 return {double(p6064) * enc1ResInv[j] * 360.0, enc1Mount[j]};
1401 if (enc2Mount[j] != Impl::Mount::None && enc2ResInv[j] != 0.0)
1402 return {double(p6064) * enc2ResInv[j] * 360.0, enc2Mount[j]};
1403 return {0.0, Impl::Mount::None};
1404 }
1405 }
1406 };
1407 // Convert velocity source to deg/s on its own physical shaft
1408 auto velDegSOnOwnShaft = [&](VelSrc s) -> std::pair<double, Mount> {
1409 const double k = this->velToDegS[j]; // 1 device unit -> k deg/s
1410 switch (s)
1411 {
1412 case Impl::VelSrc::Enc1:
1413 // Direct encoder 1 velocity (already in RPM from PDO)
1414 return {double(vE1) * k, enc1Mount[j]};
1415
1416 case Impl::VelSrc::Enc2:
1417 // Direct encoder 2 velocity (already in RPM from PDO)
1418 return {double(vE2) * k, enc2Mount[j]};
1419
1421 default: {
1422 // CiA402 standard velocity (0x606C)
1423 // Per Synapticon docs, 0x606C is reported in the POSITION reference frame
1424 // ("driving shaft"). That is, if a Position encoder is configured, 606C is
1425 // scaled to that shaft (typically the joint/load). Only when no position
1426 // encoder exists, it falls back to the velocity/torque encoder shaft (often
1427 // motor).
1428 // Therefore, select the mount based on the POSITION loop source (0x2012:09),
1429 // not the velocity loop source.
1430
1431 // Primary: use reported position loop source
1433 return {double(v606C) * k, enc1Mount[j]};
1435 return {double(v606C) * k, enc2Mount[j]};
1436
1437 // Fallback heuristics when 0x2012:09 is Unknown:
1438 // - If we have a joint-side encoder on enc2 (typical dual-encoder setup),
1439 // assume 606C is joint-side.
1440 if (enc2Mount[j] == Impl::Mount::Joint)
1441 return {double(v606C) * k, enc2Mount[j]};
1442 // - Else prefer enc1 if present; otherwise enc2; else unknown
1443 if (enc1Mount[j] != Impl::Mount::None)
1444 return {double(v606C) * k, enc1Mount[j]};
1445 if (enc2Mount[j] != Impl::Mount::None)
1446 return {double(v606C) * k, enc2Mount[j]};
1447 return {0.0, Impl::Mount::None};
1448 }
1449 }
1450 };
1451
1452 // =====================================================================
1453 // POSITION FEEDBACK PROCESSING
1454 // =====================================================================
1455 // Apply the configured source selection and coordinate transformations
1456 {
1457 // Get raw position data from configured sources (on their own shafts)
1458 auto [degJ_src, mountJ] = posDegOnOwnShaft(posSrcJoint[j]); // Joint position source
1459 auto [degM_src, mountM] = posDegOnOwnShaft(posSrcMotor[j]); // Motor position source
1460
1461 // Transform to the requested coordinate systems
1462 const double jointDeg = shaftFromMount_pos(degJ_src, mountJ, j, /*asMotor*/ false);
1463 const double motorDeg = shaftFromMount_pos(degM_src, mountM, j, /*asMotor*/ true);
1464
1465 // Store in output variables
1466 this->variables.jointPositions[j]
1467 = this->invertedMotionSenseDirection[j] ? -jointDeg : jointDeg;
1468 this->variables.motorEncoders[j] //
1469 = this->invertedMotionSenseDirection[j] ? -motorDeg : motorDeg;
1470 }
1471
1472 // =====================================================================
1473 // VELOCITY FEEDBACK PROCESSING
1474 // =====================================================================
1475 // Same logic as position but for velocities
1476 {
1477 // Get raw velocity data from configured sources (on their own shafts)
1478 auto [degsJ_src, mountJ] = velDegSOnOwnShaft(velSrcJoint[j]); // Joint velocity
1479 // source
1480 auto [degsM_src, mountM] = velDegSOnOwnShaft(velSrcMotor[j]); // Motor velocity
1481 // source
1482
1483 // Transform to the requested coordinate systems
1484 const double jointDegS
1485 = shaftFromMount_vel(degsJ_src, mountJ, j, /*asMotor*/ false);
1486 const double motorDegS = shaftFromMount_vel(degsM_src, mountM, j, /*asMotor*/ true);
1487
1488 // Store in output variables
1489 this->variables.jointVelocities[j]
1490 = this->invertedMotionSenseDirection[j] ? -jointDegS : jointDegS;
1491 this->variables.motorVelocities[j]
1492 = this->invertedMotionSenseDirection[j] ? -motorDegS : motorDegS;
1493 }
1494
1495 // =====================================================================
1496 // OTHER FEEDBACK PROCESSING
1497 // =====================================================================
1498
1499 // Accelerations not provided by the drives (would require differentiation)
1500 this->variables.jointAccelerations[j] = 0.0;
1501 this->variables.motorAccelerations[j] = 0.0;
1502
1503 // --------- Torque feedback (motor → joint conversion) ----------
1504 // CiA402 torque feedback (0x6077) is always motor-side, per-thousand of rated torque
1505 const double tq_per_thousand
1506 = double(tx.get<int16_t>(CiA402::TxField::Torque6077, 0)) / 1000.0;
1507 const double motorNm = tq_per_thousand * this->ratedMotorTorqueNm[j];
1508 // Convert motor torque to joint torque using gear ratio
1509 const double signedMotorNm = this->invertedMotionSenseDirection[j] ? -motorNm : motorNm;
1510 this->variables.jointTorques[j] = signedMotorNm * this->gearRatio[j];
1511 this->variables.motorCurrents[j] = signedMotorNm / this->torqueConstants[j];
1512
1513 // --------- Safety signals (if mapped into PDOs) ----------
1514 // These provide real-time status of safety functions
1515 this->variables.STO[j] = tx.has(CiA402::TxField::STO_6621_01)
1516 ? tx.get<uint8_t>(CiA402::TxField::STO_6621_01)
1517 : 0; // Safe Torque Off status
1518 this->variables.SBC[j] = tx.has(CiA402::TxField::SBC_6621_02)
1519 ? tx.get<uint8_t>(CiA402::TxField::SBC_6621_02)
1520 : 0; // Safe Brake Control status
1521
1522 // --------- Timestamp (if available) ----------
1523 // Provides drive-side timing information for synchronization
1525 {
1526 const uint32_t raw = tx.get<uint32_t>(CiA402::TxField::Timestamp20F0, 0);
1527 // Unwrap 32-bit microsecond counter with threshold to avoid false wraps
1528 // due to small, non-monotonic clock adjustments.
1529 // Consider a wrap only if the backward jump is larger than half the range.
1530 if (raw < this->tsLastRaw[j])
1531 {
1532 const uint32_t back = this->tsLastRaw[j] - raw;
1533 if (back > TIMESTAMP_WRAP_HALF_RANGE)
1534 {
1535 this->tsWraps[j] += 1u;
1536 }
1537 // else: small backward step → no wraps increment
1538 }
1539 this->tsLastRaw[j] = raw;
1540
1541 const uint64_t us_ext
1542 = this->tsWraps[j] * TIMESTAMP_WRAP_PERIOD_US + static_cast<uint64_t>(raw);
1543 this->variables.feedbackTime[j]
1544 = static_cast<double>(us_ext) * MICROSECONDS_TO_SECONDS;
1545 } else
1546 {
1547 this->variables.feedbackTime[j] = 0.0;
1548 }
1549
1550 // the temperature is given in mC we need to convert Celsius
1551 this->variables.driveTemperatures[j]
1553 ? double(tx.get<int32_t>(CiA402::TxField::TemperatureDrive, 0)) * 1e-3
1554 : 0.0;
1555 }
1556
1557 return true;
1558 }
1559
1560 //--------------------------------------------------------------------------
1561 // YARP ➜ CiA-402 (Op-mode sent in RxPDO::OpMode)
1562 //--------------------------------------------------------------------------
1563 static int yarpToCiaOp(int cm)
1564 {
1565 using namespace yarp::dev;
1566 switch (cm)
1567 {
1568 case VOCAB_CM_IDLE:
1569 case VOCAB_CM_FORCE_IDLE:
1570 return 0; // “No mode” → disables the power stage
1571 case VOCAB_CM_POSITION:
1572 return 1; // Profile-Position (PP)
1573 case VOCAB_CM_VELOCITY:
1574 return 9; // Cyclic-Synch-Velocity (CSV)
1575 case VOCAB_CM_TORQUE:
1576 case VOCAB_CM_CURRENT:
1577 return 10; // Cyclic-Synch-Torque (CST)
1578 case VOCAB_CM_POSITION_DIRECT:
1579 return 8; // Cyclic-Synch-Position (CSP)
1580 default:
1581 return -1; // not supported
1582 }
1583 }
1584
1585 //--------------------------------------------------------------------------
1586 // CiA-402 ➜ YARP (decode for diagnostics)
1587 //--------------------------------------------------------------------------
1588 int ciaOpToYarpWithFlavor(int op, int cstFlavor)
1589 {
1590 if (op == 10)
1591 {
1592 return (cstFlavor == VOCAB_CM_CURRENT) ? VOCAB_CM_CURRENT : VOCAB_CM_TORQUE;
1593 }
1594 return this->ciaOpToYarp(op);
1595 }
1596
1597 static int ciaOpToYarp(int op)
1598 {
1599 using namespace yarp::dev;
1600 switch (op)
1601 {
1602 case 0:
1603 return VOCAB_CM_IDLE;
1604 case 1:
1605 return VOCAB_CM_POSITION;
1606 case 3:
1607 return VOCAB_CM_VELOCITY; // PP-vel still possible
1608 case 8:
1609 return VOCAB_CM_POSITION_DIRECT;
1610 case 9:
1611 return VOCAB_CM_VELOCITY;
1612 case 10:
1613 return VOCAB_CM_TORQUE;
1614 default:
1615 return VOCAB_CM_UNKNOWN;
1616 }
1617 }
1618
1619 static std::string_view yarpToString(int op)
1620 {
1621 using namespace yarp::dev;
1622 switch (op)
1623 {
1624 case VOCAB_CM_IDLE:
1625 return "VOCAB_CM_IDLE";
1626 case VOCAB_CM_FORCE_IDLE:
1627 return "VOCAB_CM_FORCE_IDLE";
1628 case VOCAB_CM_POSITION:
1629 return "VOCAB_CM_POSITION";
1630 case VOCAB_CM_VELOCITY:
1631 return "VOCAB_CM_VELOCITY";
1632 case VOCAB_CM_TORQUE:
1633 return "VOCAB_CM_TORQUE";
1634 case VOCAB_CM_CURRENT:
1635 return "VOCAB_CM_CURRENT";
1636 case VOCAB_CM_POSITION_DIRECT:
1637 return "VOCAB_CM_POSITION_DIRECT";
1638 default:
1639 return "UNKNOWN";
1640 }
1641 }
1642
1643 /**
1644 * Decode CiA 402 error code (0x603F:00) into a human‑readable string.
1645 * Includes explicit vendor codes seen in the field and broader family fallbacks.
1646 */
1648 {
1649 switch (code)
1650 {
1651 case 0x0000:
1652 return "No fault";
1653
1654 // === Your explicit mappings ===
1655 case 0x2220:
1656 return "Continuous over current (device internal)";
1657 case 0x2250:
1658 return "Short circuit (device internal)";
1659 case 0x2350:
1660 return "Load level fault (I2t, thermal state)";
1661 case 0x2351:
1662 return "Load level warning (I2t, thermal state)";
1663 case 0x3130:
1664 return "Phase failure";
1665 case 0x3131:
1666 return "Phase failure L1";
1667 case 0x3132:
1668 return "Phase failure L2";
1669 case 0x3133:
1670 return "Phase failure L3";
1671 case 0x3210:
1672 return "DC link over-voltage";
1673 case 0x3220:
1674 return "DC link under-voltage";
1675 case 0x3331:
1676 return "Field circuit interrupted";
1677 case 0x4210:
1678 return "Excess temperature device";
1679 case 0x4310:
1680 return "Excess temperature drive";
1681 case 0x5200:
1682 return "Control";
1683 case 0x5300:
1684 return "Operating unit";
1685 case 0x6010:
1686 return "Software reset (watchdog)";
1687 case 0x6320:
1688 return "Parameter error";
1689 case 0x7121:
1690 return "Motor blocked";
1691 case 0x7300:
1692 return "Sensor";
1693 case 0x7303:
1694 return "Resolver 1 fault";
1695 case 0x7304:
1696 return "Resolver 2 fault";
1697 case 0x7500:
1698 return "Communication";
1699 case 0x8612:
1700 return "Positioning controller (reference limit)";
1701 case 0xF002:
1702 return "Sub-synchronous run";
1703
1704 default:
1705 // === Family fallbacks (upper byte) ===
1706 switch (code & 0xFF00)
1707 {
1708 case 0x2200:
1709 return "Current/device-internal fault";
1710 case 0x2300:
1711 return "Motor/output circuit fault";
1712 case 0x3100:
1713 return "Phase/mains supply issue";
1714 case 0x3200:
1715 return "DC link voltage issue";
1716 case 0x3300:
1717 return "Field/armature circuit issue";
1718 case 0x4200:
1719 return "Excess temperature (device)";
1720 case 0x4300:
1721 return "Excess temperature (drive)";
1722 case 0x5200:
1723 return "Control device hardware / limits";
1724 case 0x5300:
1725 return "Operating unit / safety";
1726 case 0x6000:
1727 return "Software reset / watchdog";
1728 case 0x6300:
1729 return "Parameter/configuration error";
1730 case 0x7100:
1731 return "Motor blocked / mechanical issue";
1732 case 0x7300:
1733 return "Sensor/encoder fault";
1734 case 0x7500:
1735 return "Communication/internal";
1736 case 0x8600:
1737 return "Positioning controller (vendor specific)";
1738 case 0xF000:
1739 return "Timing/performance warning";
1740 default: {
1741 char buf[64];
1742 std::snprintf(buf, sizeof(buf), "Unknown 0x603F error: 0x%04X", code);
1743 return std::string(buf);
1744 }
1745 }
1746 }
1747 }
1748
1749}; // struct Impl
1750
1751// CiA402MotionControl — ctor / dtor
1752
1753CiA402MotionControl::CiA402MotionControl(double period, yarp::os::ShouldUseSystemClock useSysClock)
1754 : yarp::os::PeriodicThread(period, useSysClock, yarp::os::PeriodicThreadClock::Absolute)
1755 , m_impl(std::make_unique<Impl>())
1756{
1757}
1758
1760 : yarp::os::PeriodicThread(0.001 /*1 kHz*/,
1761 yarp::os::ShouldUseSystemClock::Yes,
1762 yarp::os::PeriodicThreadClock::Absolute)
1763 , m_impl(std::make_unique<Impl>())
1764{
1765}
1766
1768
1769// open() — bring the ring to OPERATIONAL and start the cyclic thread
1770
1771bool CiA402MotionControl::open(yarp::os::Searchable& cfg)
1772{
1773 constexpr auto logPrefix = "[open]";
1774
1775 // ---------------------------------------------------------------------
1776 // Parse driver parameters
1777 // ---------------------------------------------------------------------
1778 if (!cfg.check("ifname") || !cfg.find("ifname").isString())
1779 {
1780 yCError(CIA402, "%s: 'ifname' parameter is not a string", Impl::kClassName.data());
1781 return false;
1782 }
1783 if (!cfg.check("num_axes") || !cfg.find("num_axes").isInt32())
1784 {
1785 yCError(CIA402, "%s: 'num_axes' parameter is not an integer", Impl::kClassName.data());
1786 return false;
1787 }
1788
1789 if (!cfg.check("period") || !cfg.find("period").isFloat64())
1790 {
1791 yCError(CIA402, "%s: 'period' parameter is not a float64", Impl::kClassName.data());
1792 return false;
1793 }
1794 const double period = cfg.find("period").asFloat64();
1795 if (period <= 0.0)
1796 {
1797 yCError(CIA402, "%s: 'period' parameter must be positive", Impl::kClassName.data());
1798 return false;
1799 }
1800 this->setPeriod(period);
1801 yCDebug(CIA402, "%s: using period = %.6f s", logPrefix, period);
1802
1803 m_impl->numAxes = static_cast<size_t>(cfg.find("num_axes").asInt32());
1804 m_impl->firstSlave = cfg.check("first_slave", yarp::os::Value(1)).asInt32();
1805 if (cfg.check("expected_slave_name"))
1806 m_impl->expectedName = cfg.find("expected_slave_name").asString();
1807
1808 // =========================================================================
1809 // ENCODER CONFIGURATION PARSING
1810 // =========================================================================
1811 // This system supports dual encoders per axis with flexible source selection:
1812 // - Enc1: Typically motor-mounted (high resolution, motor shaft feedback)
1813 // - Enc2: Typically joint-mounted (load-side feedback after gearbox)
1814 // - 6064/606C: Standard CiA402 objects that follow the configured loop sources
1815 //
1816 // Each feedback type (position/velocity for joint/motor) can independently
1817 // choose its source, allowing configurations like:
1818 // - Joint position from load encoder, motor position from motor encoder
1819 // - Joint velocity from load encoder, motor velocity from 606C
1820
1821 // Parse helper functions for configuration strings
1822 auto parsePos = [&](const std::string& s) -> Impl::PosSrc {
1823 if (s == "enc1")
1824 return Impl::PosSrc::Enc1; // Use encoder 1 directly
1825 if (s == "enc2")
1826 return Impl::PosSrc::Enc2; // Use encoder 2 directly
1827 return Impl::PosSrc::S6064; // Use CiA402 standard object (follows loop source)
1828 };
1829 auto parseVel = [&](const std::string& s) -> Impl::VelSrc {
1830 if (s == "enc1")
1831 return Impl::VelSrc::Enc1; // Use encoder 1 velocity directly
1832 if (s == "enc2")
1833 return Impl::VelSrc::Enc2; // Use encoder 2 velocity directly
1834 return Impl::VelSrc::S606C; // Use CiA402 standard object (follows loop source)
1835 };
1836 auto parseMount = [&](const std::string& s) -> Impl::Mount {
1837 if (s == "motor")
1838 return Impl::Mount::Motor; // Encoder measures motor shaft (pre-gearbox)
1839 if (s == "joint")
1840 return Impl::Mount::Joint; // Encoder measures joint/load shaft (post-gearbox)
1841 if (s == "none")
1842 return Impl::Mount::None; // Encoder not present/not used
1843 yWarning("%s: invalid mount '%s' (allowed: none|motor|joint) → 'none'",
1844 Impl::kClassName.data(),
1845 s.c_str());
1846 return Impl::Mount::None;
1847 };
1848
1849 auto extractListOfStringFromSearchable = [this](const yarp::os::Searchable& cfg,
1850 const char* key,
1851 const std::vector<std::string>& acceptedKeys,
1852 std::vector<std::string>& result) -> bool {
1853 result.clear();
1854
1855 if (!cfg.check(key))
1856 {
1857 yCError(CIA402, "%s: missing key '%s'", Impl::kClassName.data(), key);
1858 return false;
1859 }
1860
1861 const yarp::os::Value& v = cfg.find(key);
1862 if (!v.isList())
1863 {
1864 yCError(CIA402, "%s: key '%s' is not a list", Impl::kClassName.data(), key);
1865 return false;
1866 }
1867
1868 const yarp::os::Bottle* lst = v.asList();
1869 if (!lst)
1870 {
1871 yCError(CIA402,
1872 "%s: internal error: list for key '%s' is null",
1873 Impl::kClassName.data(),
1874 key);
1875 return false;
1876 }
1877
1878 const size_t expected = static_cast<size_t>(m_impl->numAxes);
1879 const size_t actual = static_cast<size_t>(lst->size());
1880 if (actual != expected)
1881 {
1882 yCError(CIA402,
1883 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
1884 Impl::kClassName.data(),
1885 key,
1886 actual,
1887 expected);
1888 return false;
1889 }
1890
1891 result.reserve(expected);
1892 for (int i = 0; i < lst->size(); ++i)
1893 {
1894 const yarp::os::Value& elem = lst->get(i);
1895
1896 if (!elem.isString())
1897 {
1898 yCError(CIA402,
1899 "%s: element %d in list for key '%s' is not a string",
1900 Impl::kClassName.data(),
1901 i,
1902 key);
1903 result.clear();
1904 return false;
1905 }
1906
1907 const std::string val = elem.asString();
1908
1909 // if acceptedKeys is non-empty, validate the value
1910 if (!acceptedKeys.empty())
1911 {
1912 if (std::find(acceptedKeys.begin(), acceptedKeys.end(), val) == acceptedKeys.end())
1913 {
1914 yCError(CIA402,
1915 "%s: invalid value '%s' in list for key '%s'",
1916 Impl::kClassName.data(),
1917 val.c_str(),
1918 key);
1919 result.clear();
1920 return false;
1921 }
1922 }
1923 result.push_back(val);
1924 }
1925
1926 return true;
1927 };
1928
1929 auto extractListOfDoubleFromSearchable = [this](const yarp::os::Searchable& cfg,
1930 const char* key,
1931 std::vector<double>& result) -> bool {
1932 result.clear();
1933
1934 if (!cfg.check(key))
1935 {
1936 yCError(CIA402, "%s: missing key '%s'", Impl::kClassName.data(), key);
1937 return false;
1938 }
1939
1940 const yarp::os::Value& v = cfg.find(key);
1941 if (!v.isList())
1942 {
1943 yCError(CIA402, "%s: key '%s' is not a list", Impl::kClassName.data(), key);
1944 return false;
1945 }
1946
1947 const yarp::os::Bottle* lst = v.asList();
1948 if (!lst)
1949 {
1950 yCError(CIA402,
1951 "%s: internal error: list for key '%s' is null",
1952 Impl::kClassName.data(),
1953 key);
1954 return false;
1955 }
1956
1957 const size_t expected = static_cast<size_t>(m_impl->numAxes);
1958 const size_t actual = static_cast<size_t>(lst->size());
1959 if (actual != expected)
1960 {
1961 yCError(CIA402,
1962 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
1963 Impl::kClassName.data(),
1964 key,
1965 actual,
1966 expected);
1967 return false;
1968 }
1969
1970 result.reserve(expected);
1971 for (int i = 0; i < lst->size(); ++i)
1972 {
1973 const yarp::os::Value& elem = lst->get(i);
1974
1975 if (!elem.isFloat64() && !elem.isInt32() && !elem.isInt64() && !elem.isFloat32())
1976 {
1977 yCError(CIA402,
1978 "%s: element %d in list for key '%s' is not a number",
1979 Impl::kClassName.data(),
1980 i,
1981 key);
1982 result.clear();
1983 return false;
1984 }
1985
1986 result.push_back(elem.asFloat64());
1987 }
1988
1989 return true;
1990 };
1991
1992 auto extractListOfBoolFromSearchable = [this](const yarp::os::Searchable& cfg,
1993 const char* key,
1994 std::vector<bool>& result) -> bool {
1995 result.clear();
1996
1997 if (!cfg.check(key))
1998 {
1999 yCError(CIA402, "%s: missing key '%s'", Impl::kClassName.data(), key);
2000 return false;
2001 }
2002
2003 const yarp::os::Value& v = cfg.find(key);
2004 if (!v.isList())
2005 {
2006 yCError(CIA402, "%s: key '%s' is not a list", Impl::kClassName.data(), key);
2007 return false;
2008 }
2009
2010 const yarp::os::Bottle* lst = v.asList();
2011 if (!lst)
2012 {
2013 yCError(CIA402,
2014 "%s: internal error: list for key '%s' is null",
2015 Impl::kClassName.data(),
2016 key);
2017 return false;
2018 }
2019
2020 const size_t expected = static_cast<size_t>(m_impl->numAxes);
2021 const size_t actual = static_cast<size_t>(lst->size());
2022 if (actual != expected)
2023 {
2024 yCError(CIA402,
2025 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
2026 Impl::kClassName.data(),
2027 key,
2028 actual,
2029 expected);
2030 return false;
2031 }
2032
2033 result.reserve(expected);
2034 for (int i = 0; i < lst->size(); ++i)
2035 {
2036 const yarp::os::Value& elem = lst->get(i);
2037
2038 if (!elem.isBool())
2039 {
2040 yCError(CIA402,
2041 "%s: element %d in list for key '%s' is not a boolean",
2042 Impl::kClassName.data(),
2043 i,
2044 key);
2045 result.clear();
2046 return false;
2047 }
2048
2049 result.push_back(elem.asBool());
2050 }
2051
2052 return true;
2053 };
2054
2055 // Encoder mounting configuration (where each encoder is physically located)
2056 // enc1_mount must be list of "motor" or "joint"
2057 // enc2_mount must be list of "motor", "joint" or "none"
2058 std::vector<std::string> enc1MStr; // encoder 1 mount per axis
2059 std::vector<std::string> enc2MStr; // encoder 2 mount per axis
2060
2061 if (!extractListOfStringFromSearchable(cfg, "enc1_mount", {"motor", "joint"}, enc1MStr))
2062 return false;
2063 if (!extractListOfStringFromSearchable(cfg, "enc2_mount", {"motor", "joint", "none"}, enc2MStr))
2064 return false;
2065
2066 std::vector<std::string> posSrcJointStr;
2067 std::vector<std::string> posSrcMotorStr;
2068 std::vector<std::string> velSrcJointStr;
2069 std::vector<std::string> velSrcMotorStr;
2070 if (!extractListOfStringFromSearchable(cfg,
2071 "position_feedback_joint",
2072 {"6064", "enc1", "enc2"},
2073 posSrcJointStr))
2074 return false;
2075 if (!extractListOfStringFromSearchable(cfg,
2076 "position_feedback_motor",
2077 {"6064", "enc1", "enc2"},
2078 posSrcMotorStr))
2079 return false;
2080 if (!extractListOfStringFromSearchable(cfg,
2081 "velocity_feedback_joint",
2082 {"606C", "enc1", "enc2"},
2083 velSrcJointStr))
2084 return false;
2085 if (!extractListOfStringFromSearchable(cfg,
2086 "velocity_feedback_motor",
2087 {"606C", "enc1", "enc2"},
2088 velSrcMotorStr))
2089 return false;
2090
2091 std::vector<double> positionWindowDeg; // position window for targetReached
2092 std::vector<double> timingWindowMs; // timing window for targetReached
2093 std::vector<double> simplePidKpNmPerDeg; // optional simple PID gains
2094 std::vector<double> simplePidKdNmSecPerDeg;
2095
2096 constexpr uint16_t kPositionStrategySimplePid = 1u;
2097 constexpr uint16_t kPositionStrategyCascadedPid = 2u;
2098 const bool useSimplePidMode
2099 = cfg.check("use_simple_pid_mode") ? cfg.find("use_simple_pid_mode").asBool() : false;
2100 const uint16_t desiredPositionStrategy
2101 = useSimplePidMode ? kPositionStrategySimplePid : kPositionStrategyCascadedPid;
2102
2103 if (!extractListOfDoubleFromSearchable(cfg, "position_window_deg", positionWindowDeg))
2104 return false;
2105 if (!extractListOfDoubleFromSearchable(cfg, "timing_window_ms", timingWindowMs))
2106 return false;
2107
2108 const bool hasSimplePidKpCfg = cfg.check("simple_pid_kp_nm_per_deg");
2109 const bool hasSimplePidKdCfg = cfg.check("simple_pid_kd_nm_s_per_deg");
2110 const bool programSimplePidGains = hasSimplePidKpCfg || hasSimplePidKdCfg;
2111 if (hasSimplePidKpCfg != hasSimplePidKdCfg)
2112 {
2113 yCError(CIA402,
2114 "%s configuration must provide both simple_pid_kp_nm_per_deg and "
2115 "simple_pid_kd_nm_s_per_deg",
2116 logPrefix);
2117 return false;
2118 }
2119 if (programSimplePidGains)
2120 {
2121 if (!extractListOfDoubleFromSearchable(cfg, "simple_pid_kp_nm_per_deg", simplePidKpNmPerDeg))
2122 return false;
2123 if (!extractListOfDoubleFromSearchable(cfg,
2124 "simple_pid_kd_nm_s_per_deg",
2125 simplePidKdNmSecPerDeg))
2126 return false;
2127 }
2128
2129 for (size_t j = 0; j < m_impl->numAxes; ++j)
2130 {
2131 m_impl->enc1Mount.push_back(parseMount(enc1MStr[j]));
2132 m_impl->enc2Mount.push_back(parseMount(enc2MStr[j]));
2133 m_impl->posSrcJoint.push_back(parsePos(posSrcJointStr[j]));
2134 m_impl->posSrcMotor.push_back(parsePos(posSrcMotorStr[j]));
2135 m_impl->velSrcJoint.push_back(parseVel(velSrcJointStr[j]));
2136 m_impl->velSrcMotor.push_back(parseVel(velSrcMotorStr[j]));
2137 }
2138
2139 const std::string ifname = cfg.find("ifname").asString();
2140 // Optional runtime knobs
2141 const int pdoTimeoutUs = cfg.check("pdo_timeout_us") ? cfg.find("pdo_timeout_us").asInt32()
2142 : -1;
2143 const bool enableDc = cfg.check("enable_dc") ? cfg.find("enable_dc").asBool() : true;
2144 const int dcShiftNs = cfg.check("dc_shift_ns") ? cfg.find("dc_shift_ns").asInt32() : 0;
2145 yCInfo(CIA402, "%s opening EtherCAT manager on interface %s", logPrefix, ifname.c_str());
2146
2147 if (!extractListOfBoolFromSearchable(cfg,
2148 "inverted_motion_sense_direction",
2149 m_impl->invertedMotionSenseDirection))
2150 return false;
2151
2152 auto vecBoolToString = [](const std::vector<bool>& v) -> std::string {
2153 std::string s;
2154 for (size_t i = 0; i < v.size(); ++i)
2155 {
2156 s += (v[i] ? "true" : "false");
2157 if (i + 1 < v.size())
2158 s += ", ";
2159 }
2160 return s;
2161 };
2162
2163 yCDebug(CIA402,
2164 "%s: inverted_motion_sense_direction = [%s]",
2165 logPrefix,
2166 vecBoolToString(m_impl->invertedMotionSenseDirection).c_str());
2167
2168 // ---------------------------------------------------------------------
2169 // Initialize the EtherCAT manager (ring in SAFE‑OP)
2170 // ---------------------------------------------------------------------
2171
2172 const auto ecErr = m_impl->ethercatManager.init(ifname);
2174 {
2175 yCError(CIA402,
2176 "%s EtherCAT initialization failed with error code %d",
2177 logPrefix,
2178 static_cast<int>(ecErr));
2179 return false;
2180 }
2181
2182 if (pdoTimeoutUs > 0)
2183 {
2184 m_impl->ethercatManager.setPdoTimeoutUs(pdoTimeoutUs);
2185 yCInfo(CIA402,
2186 "%s PDO receive timeout set to %d us",
2187 logPrefix,
2188 m_impl->ethercatManager.getPdoTimeoutUs());
2189 } else
2190 {
2191 yCInfo(CIA402,
2192 "%s using default PDO receive timeout of %d us",
2193 logPrefix,
2194 m_impl->ethercatManager.getPdoTimeoutUs());
2195 }
2196
2197 // We'll enable DC later, after going OP, using the configured period
2198 const uint32_t cycleNs = static_cast<uint32_t>(std::llround(this->getPeriod() * 1e9));
2199
2200 // =========================================================================
2201 // DRIVE LOOP SOURCE CONFIGURATION READING
2202 // =========================================================================
2203 // Read which encoders the drive uses internally for position/velocity loops
2204 // This affects how 6064/606C values should be interpreted
2205
2206 // Loop-source readers (local lambdas)
2207 auto readPosLoopSrc = [&](size_t j) -> Impl::SensorSrc {
2208 const int s = m_impl->firstSlave + int(j);
2209 uint8_t src = 0;
2210 auto e = m_impl->ethercatManager.readSDO<uint8_t>(s, 0x2012, 0x09, src);
2212 {
2213 yCError(CIA402,
2214 "%s: failed to read position loop source (joint %zu)",
2215 Impl::kClassName.data(),
2216 j);
2218 }
2219 return (src == 1) ? Impl::SensorSrc::Enc1
2220 : (src == 2) ? Impl::SensorSrc::Enc2
2222 };
2223 auto readVelLoopSrc = [&](size_t j) -> Impl::SensorSrc {
2224 const int s = m_impl->firstSlave + int(j);
2225 uint8_t src = 0;
2226 auto e = m_impl->ethercatManager.readSDO<uint8_t>(s, 0x2011, 0x05, src);
2229 return (src == 1) ? Impl::SensorSrc::Enc1
2230 : (src == 2) ? Impl::SensorSrc::Enc2
2232 };
2233
2234 // --------- PDO Mapping Availability Checks ----------
2235 // These check if encoder data was successfully mapped into the PDOs
2236 // during the EtherCAT initialization phase
2237 auto hasEnc1Pos = [&](size_t j) {
2238 const int s = m_impl->firstSlave + int(j);
2239 return m_impl->ethercatManager.getTxView(s).has(CiA402::TxField::Enc1Pos2111_02);
2240 };
2241 auto hasEnc1Vel = [&](size_t j) {
2242 const int s = m_impl->firstSlave + int(j);
2243 return m_impl->ethercatManager.getTxView(s).has(CiA402::TxField::Enc1Vel2111_03);
2244 };
2245 auto hasEnc2Pos = [&](size_t j) {
2246 const int s = m_impl->firstSlave + int(j);
2247 return m_impl->ethercatManager.getTxView(s).has(CiA402::TxField::Enc2Pos2113_02);
2248 };
2249 auto hasEnc2Vel = [&](size_t j) {
2250 const int s = m_impl->firstSlave + int(j);
2251 return m_impl->ethercatManager.getTxView(s).has(CiA402::TxField::Enc2Vel2113_03);
2252 };
2253
2254 yCInfo(CIA402,
2255 "%s using %zu axes, EtherCAT slaves %d to %d",
2256 logPrefix,
2257 m_impl->numAxes,
2258 m_impl->firstSlave,
2259 m_impl->firstSlave + int(m_impl->numAxes) - 1);
2260
2261 // --------- Read drive-internal loop sources ----------
2262 // These determine how CiA402 standard objects (6064/606C) should be interpreted
2263 m_impl->posLoopSrc.resize(m_impl->numAxes, Impl::SensorSrc::Unknown);
2264 m_impl->velLoopSrc.resize(m_impl->numAxes, Impl::SensorSrc::Unknown);
2265 for (size_t j = 0; j < m_impl->numAxes; ++j)
2266 {
2267 m_impl->posLoopSrc[j] = readPosLoopSrc(j);
2268 m_impl->velLoopSrc[j] = readVelLoopSrc(j);
2269 }
2270
2271 // =========================================================================
2272 // CONFIGURATION VALIDATION
2273 // =========================================================================
2274 // Strict validation: requested encoders must be both mapped in PDOs AND
2275 // have valid mount points. This prevents runtime errors from misconfiguration.
2276 for (size_t j = 0; j < m_impl->numAxes; ++j)
2277 {
2278 auto bad = [&](const char* what) {
2279 yCError(CIA402, "%s j=%zu invalid configuration: %s", logPrefix, j, what);
2280 return true;
2281 };
2282
2283 // --------- Position feedback validation ----------
2284 if (m_impl->posSrcJoint[j] == Impl::PosSrc::Enc1
2285 && (m_impl->enc1Mount[j] == Impl::Mount::None || !hasEnc1Pos(j)))
2286 {
2287 if (bad("pos_joint=enc1 but enc1 not mounted/mapped"))
2288 return false;
2289 }
2290 if (m_impl->posSrcJoint[j] == Impl::PosSrc::Enc2
2291 && (m_impl->enc2Mount[j] == Impl::Mount::None || !hasEnc2Pos(j)))
2292 {
2293 if (bad("pos_joint=enc2 but enc2 not mounted/mapped"))
2294 return false;
2295 }
2296
2297 if (m_impl->posSrcMotor[j] == Impl::PosSrc::Enc1
2298 && (m_impl->enc1Mount[j] == Impl::Mount::None || !hasEnc1Pos(j)))
2299 {
2300 if (bad("pos_motor=enc1 but enc1 not mounted/mapped"))
2301 return false;
2302 }
2303 if (m_impl->posSrcMotor[j] == Impl::PosSrc::Enc2
2304 && (m_impl->enc2Mount[j] == Impl::Mount::None || !hasEnc2Pos(j)))
2305 {
2306 if (bad("pos_motor=enc2 but enc2 not mounted/mapped"))
2307 return false;
2308 }
2309
2310 // --------- Velocity feedback validation ----------
2311 if (m_impl->velSrcJoint[j] == Impl::VelSrc::Enc1
2312 && (m_impl->enc1Mount[j] == Impl::Mount::None || !hasEnc1Vel(j)))
2313 {
2314 if (bad("vel_joint=enc1 but enc1 not mounted/mapped"))
2315 return false;
2316 }
2317 if (m_impl->velSrcJoint[j] == Impl::VelSrc::Enc2
2318 && (m_impl->enc2Mount[j] == Impl::Mount::None || !hasEnc2Vel(j)))
2319 {
2320 if (bad("vel_joint=enc2 but enc2 not mounted/mapped"))
2321 return false;
2322 }
2323
2324 if (m_impl->velSrcMotor[j] == Impl::VelSrc::Enc1
2325 && (m_impl->enc1Mount[j] == Impl::Mount::None || !hasEnc1Vel(j)))
2326 {
2327 if (bad("vel_motor=enc1 but enc1 not mounted/mapped"))
2328 return false;
2329 }
2330 if (m_impl->velSrcMotor[j] == Impl::VelSrc::Enc2
2331 && (m_impl->enc2Mount[j] == Impl::Mount::None || !hasEnc2Vel(j)))
2332 {
2333 if (bad("vel_motor=enc2 but enc2 not mounted/mapped"))
2334 return false;
2335 }
2336 }
2337
2338 // ---------------------------------------------------------------------
2339 // Read static SDO parameters (encoders, velocity units, gear ratios, motor limits)
2340 // ---------------------------------------------------------------------
2341 if (!m_impl->readEncoderResolutions())
2342 {
2343 yCError(CIA402, "%s failed to read encoder resolutions from SDO", logPrefix);
2344 return false;
2345 }
2346 if (!m_impl->readSiVelocityUnits())
2347 {
2348 yCError(CIA402, "%s failed to read velocity conversions from SDO", logPrefix);
2349 return false;
2350 }
2351 if (!m_impl->readGearRatios())
2352 {
2353 yCError(CIA402, "%s failed to read gear ratios from SDO", logPrefix);
2354 return false;
2355 }
2356 if (!m_impl->readMotorConstants())
2357 {
2358 yCError(CIA402, "%s failed to read motor constants from SDO", logPrefix);
2359 return false;
2360 }
2361 if (!m_impl->readTorqueValues())
2362 {
2363 yCError(CIA402, "%s failed to read torque values from SDO", logPrefix);
2364 return false;
2365 }
2366
2367 // get the current control strategy
2368 uint16_t currentStrategy = 0;
2369 if (!m_impl->getPositionControlStrategy(currentStrategy))
2370 {
2371 yCError(CIA402, "%s failed to get current control strategy", logPrefix);
2372 return false;
2373 }
2374 yCInfo(CIA402,
2375 "%s current control strategy is %u",
2376 logPrefix,
2377 static_cast<unsigned>(currentStrategy));
2378
2379
2380 yCInfo(CIA402,
2381 "%s requested position strategy %u (%s)",
2382 logPrefix,
2383 static_cast<unsigned>(desiredPositionStrategy),
2384 useSimplePidMode ? "simple PID" : "cascaded PID");
2385
2386 if (!m_impl->setPositionControlStrategy(desiredPositionStrategy))
2387 {
2388 yCError(CIA402, "%s failed to configure position control strategy", logPrefix);
2389 return false;
2390 }
2391
2392 // get again the control strategy to verify
2393 if (!m_impl->getPositionControlStrategy(currentStrategy))
2394 {
2395 yCError(CIA402, "%s failed to get current control strategy", logPrefix);
2396 return false;
2397 }
2398 yCInfo(CIA402,
2399 "%s current control strategy after configuration is %u",
2400 logPrefix,
2401 static_cast<unsigned>(currentStrategy));
2402
2403 const bool enableSimplePidGainsIo = (desiredPositionStrategy == kPositionStrategySimplePid);
2404 if (!enableSimplePidGainsIo && programSimplePidGains)
2405 {
2406 yCWarning(CIA402,
2407 "%s simple PID gains provided but position strategy is not simple PID; skipping "
2408 "0x2012 gains programming",
2409 logPrefix);
2410 }
2411
2412 if (enableSimplePidGainsIo && programSimplePidGains)
2413 {
2414 if (!m_impl->configureSimplePidGains(simplePidKpNmPerDeg, simplePidKdNmSecPerDeg))
2415 {
2416 yCError(CIA402, "%s failed to program simple PID gains", logPrefix);
2417 return false;
2418 }
2419 } else if (enableSimplePidGainsIo)
2420 {
2421 yCDebug(CIA402,
2422 "%s skipping simple PID gains programming (config keys not provided)",
2423 logPrefix);
2424 }
2425
2426 std::vector<double> readKp;
2427 std::vector<double> readKd;
2428 bool simplePidGainsAvailable = false;
2429 if (enableSimplePidGainsIo)
2430 {
2431 // read the simple PID gains to verify
2432 if (!m_impl->readSimplePidGains(readKp, readKd))
2433 {
2434 yCError(CIA402, "%s failed to read back simple PID gains", logPrefix);
2435 return false;
2436 }
2437 simplePidGainsAvailable = true;
2438
2439 for (size_t j = 0; j < m_impl->numAxes; ++j)
2440 {
2441 yCDebug(CIA402,
2442 "%s j=%zu simple PID gains: Kp=%.6f Nm/deg, Kd=%.6f Nm·s/deg",
2443 logPrefix,
2444 j,
2445 readKp[j],
2446 readKd[j]);
2447 }
2448 }
2449
2450 // ---------------------------------------------------------------------
2451 // Set the position limits (SDO 607D)
2452 // ---------------------------------------------------------------------
2453 if (!extractListOfDoubleFromSearchable(cfg,
2454 "pos_limit_min_deg",
2455 m_impl->limits.minPositionLimitDeg))
2456 {
2457 yCError(CIA402, "%s failed to parse pos_limit_min_deg", logPrefix);
2458 return false;
2459 }
2460 if (!extractListOfDoubleFromSearchable(cfg,
2461 "pos_limit_max_deg",
2462 m_impl->limits.maxPositionLimitDeg))
2463 {
2464 yCError(CIA402, "%s failed to parse pos_limit_max_deg", logPrefix);
2465 return false;
2466 }
2467 if (!extractListOfBoolFromSearchable(cfg,
2468 "use_position_limits_from_config",
2469 m_impl->limits.usePositionLimitsFromConfig))
2470 {
2471 yCError(CIA402, "%s failed to parse use_position_limits_from_config", logPrefix);
2472 return false;
2473 }
2474
2475 if (m_impl->limits.minPositionLimitDeg.size() != m_impl->numAxes
2476 || m_impl->limits.maxPositionLimitDeg.size() != m_impl->numAxes
2477 || m_impl->limits.usePositionLimitsFromConfig.size() != m_impl->numAxes)
2478 {
2479 yCError(CIA402,
2480 "%s position limit lists must have exactly %zu elements",
2481 logPrefix,
2482 m_impl->numAxes);
2483 return false;
2484 }
2485
2486 for (size_t j = 0; j < m_impl->numAxes; ++j)
2487 {
2488 const bool inv = m_impl->invertedMotionSenseDirection[j];
2489
2490 if (m_impl->limits.usePositionLimitsFromConfig[j])
2491 {
2492 // Convert joint degrees to loop-shaft counts and write to SDO 0x607D
2493 const int32_t lowerCounts
2494 = m_impl->jointDegToTargetCounts(j, m_impl->limits.minPositionLimitDeg[j]);
2495 const int32_t upperCounts
2496 = m_impl->jointDegToTargetCounts(j, m_impl->limits.maxPositionLimitDeg[j]);
2497
2498 int32_t minCounts = 0;
2499 int32_t maxCounts = 0;
2500 if (!inv)
2501 {
2502 minCounts = lowerCounts;
2503 maxCounts = upperCounts;
2504 } else
2505 {
2506 // Decreasing mapping f(x) = -counts(x) → [L, U] maps to [f(U), f(L)]
2507 minCounts = -upperCounts;
2508 maxCounts = -lowerCounts;
2509 }
2510
2511 if (!m_impl->setPositionCountsLimits(j, minCounts, maxCounts))
2512 {
2513 yCError(CIA402, "%s j=%zu failed to set position limits", logPrefix, j);
2514 return false;
2515 }
2516 } else
2517 {
2518 // Read 0x607D:min/max from SDO, convert to degrees, and cache into limits vectors.
2519 const int s = m_impl->firstSlave + static_cast<int>(j);
2520 int32_t minCounts = 0;
2521 int32_t maxCounts = 0;
2522 auto e1 = m_impl->ethercatManager.readSDO<int32_t>(s, 0x607D, 0x01, minCounts);
2523 auto e2 = m_impl->ethercatManager.readSDO<int32_t>(s, 0x607D, 0x02, maxCounts);
2526 {
2527 yCError(CIA402, "%s j=%zu failed to read position limits from SDO", logPrefix, j);
2528 return false;
2529 }
2530
2531 // Convert counts back to joint-space degrees.
2532 double minDeg = 0.0;
2533 double maxDeg = 0.0;
2534 if (!inv)
2535 {
2536 minDeg = m_impl->targetCountsToJointDeg(j, minCounts);
2537 maxDeg = m_impl->targetCountsToJointDeg(j, maxCounts);
2538 } else
2539 {
2540 // When inverted, SDO holds [-U, -L]; swap to recover [L, U] in degrees.
2541 minDeg = m_impl->targetCountsToJointDeg(j, maxCounts);
2542 maxDeg = m_impl->targetCountsToJointDeg(j, minCounts);
2543 }
2544
2545 m_impl->limits.minPositionLimitDeg[j] = minDeg;
2546 m_impl->limits.maxPositionLimitDeg[j] = maxDeg;
2547 }
2548 }
2549
2550 // ---------------------------------------------------------------------
2551 // Idle all drives (switch‑on disabled, no mode selected)
2552 // ---------------------------------------------------------------------
2553 for (size_t j = 0; j < m_impl->numAxes; ++j)
2554 {
2555 const int slave = m_impl->firstSlave + static_cast<int>(j);
2556 auto* rx = m_impl->ethercatManager.getRxPDO(slave);
2557 if (!rx)
2558 {
2559 yCError(CIA402, "%s invalid slave index %d for axis %zu", logPrefix, slave, j);
2560 return false;
2561 }
2562 rx->Controlword = 0x0000;
2563 rx->OpMode = 0;
2564 }
2565
2566 // Send one frame so the outputs take effect
2567 if (m_impl->ethercatManager.sendReceive() != ::CiA402::EthercatManager::Error::NoError)
2568 {
2569 yCError(CIA402, "%s initial EtherCAT send/receive after SDO reading failed", logPrefix);
2570 return false;
2571 }
2572
2573 // ---------------------------------------------------------------------
2574 // Configure position windows (targetReached thresholds)
2575 // ---------------------------------------------------------------------
2576 for (int j = 0; j < m_impl->numAxes; ++j)
2577 {
2578 if (!m_impl->setPositionWindowDeg(j, positionWindowDeg[j], timingWindowMs[j]))
2579 {
2580 yCError(CIA402, "%s j=%d failed to set position window", logPrefix, j);
2581 return false;
2582 }
2583 }
2584
2585 // ---------------------------------------------------------------------
2586 // Allocate runtime containers and CiA‑402 state machines
2587 // ---------------------------------------------------------------------
2588
2589 m_impl->variables.resizeContainers(m_impl->numAxes);
2590 m_impl->setPoints.resize(m_impl->numAxes);
2591 m_impl->setPoints.reset();
2592 m_impl->controlModeState.resize(m_impl->numAxes);
2593 m_impl->sm.resize(m_impl->numAxes);
2594 m_impl->velLatched.assign(m_impl->numAxes, false);
2595 m_impl->trqLatched.assign(m_impl->numAxes, false);
2596 m_impl->currLatched.assign(m_impl->numAxes, false);
2597 m_impl->posLatched.assign(m_impl->numAxes, false);
2598 m_impl->torqueSeedNm.assign(m_impl->numAxes, 0.0);
2599 m_impl->tsLastRaw.assign(m_impl->numAxes, 0u);
2600 m_impl->tsWraps.assign(m_impl->numAxes, 0u);
2601 m_impl->ppState.ppRefSpeedDegS.assign(m_impl->numAxes, 0.0);
2602 m_impl->ppState.ppRefAccelerationDegSS.assign(m_impl->numAxes, 0.0);
2603 m_impl->ppState.ppHaltRequested.assign(m_impl->numAxes, false);
2604
2605 for (size_t j = 0; j < m_impl->numAxes; ++j)
2606 {
2607 m_impl->sm[j] = std::make_unique<CiA402::StateMachine>();
2608 m_impl->sm[j]->reset();
2609 }
2610
2611 // get the axes names (if available)
2612 if (!extractListOfStringFromSearchable(cfg, "axes_names", {}, m_impl->variables.jointNames))
2613 return false;
2614
2615 constexpr double initialPositionVelocityDegs = 10;
2616 for (size_t j = 0; j < m_impl->numAxes; ++j)
2617 {
2618 // Cache for getRefSpeed()
2619 {
2620 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
2621 m_impl->ppState.ppRefSpeedDegS[j] = initialPositionVelocityDegs;
2622 }
2623 m_impl->setSDORefSpeed(j, initialPositionVelocityDegs);
2624 }
2625
2626 yCInfo(CIA402, "%s opened %zu axes, initialization complete", logPrefix, m_impl->numAxes);
2627
2628 // ---------------------------------------------------------------------
2629 // Transition to OPERATIONAL and enable DC
2630 // ---------------------------------------------------------------------
2631 {
2632 const auto opErr = m_impl->ethercatManager.goOperational();
2634 {
2635 yCError(CIA402, "%s failed to enter OPERATIONAL state", logPrefix);
2636 return false;
2637 }
2638
2639 if (enableDc)
2640 {
2641 const auto dcErr
2642 = m_impl->ethercatManager.enableDCSync0(cycleNs, /*shift_ns=*/dcShiftNs);
2644 {
2645 yCError(CIA402, "%s failed to enable DC SYNC0", logPrefix);
2646 return false;
2647 }
2648 } else
2649 {
2650 yWarning("%s DC synchronization disabled by configuration", logPrefix);
2651 }
2652 }
2653
2654 // ---------------------------------------------------------------------
2655 // Startup safety check: verify joints are within limits
2656 // ---------------------------------------------------------------------
2657 {
2658 // Refresh PDO inputs once so feedback reflects the current position
2659 if (m_impl->ethercatManager.sendReceive() != ::CiA402::EthercatManager::Error::NoError)
2660 {
2661 yCError(CIA402, "%s initial send/receive in OPERATIONAL failed", logPrefix);
2662 return false;
2663 }
2664
2665 (void)m_impl->readFeedback();
2666
2667 bool outOfLimits = false;
2668 for (size_t j = 0; j < m_impl->numAxes; ++j)
2669 {
2670 const double posDeg = m_impl->variables.jointPositions[j];
2671 const double minDeg = m_impl->limits.minPositionLimitDeg[j];
2672 const double maxDeg = m_impl->limits.maxPositionLimitDeg[j];
2673
2674 const bool belowMin = (posDeg < minDeg);
2675 const bool aboveMax = (posDeg > maxDeg);
2676
2677 if (belowMin || aboveMax)
2678 {
2679 const char* axisLabel = nullptr;
2680 if (j < m_impl->variables.jointNames.size()
2681 && !m_impl->variables.jointNames[j].empty())
2682 {
2683 axisLabel = m_impl->variables.jointNames[j].c_str();
2684 }
2685
2686 yCError(CIA402,
2687 "%s joint %zu%s%s%s out of limits: pos=%.6f deg, min=%.6f, max=%.6f. "
2688 "Move the joint within limits before starting.",
2689 logPrefix,
2690 j,
2691 axisLabel ? " (" : "",
2692 axisLabel ? axisLabel : "",
2693 axisLabel ? ")" : "",
2694 posDeg,
2695 minDeg,
2696 maxDeg);
2697 outOfLimits = true;
2698 }
2699 }
2700
2701 if (outOfLimits)
2702 {
2703 // Disable power stage before aborting
2704 for (size_t j = 0; j < m_impl->numAxes; ++j)
2705 {
2706 const int slave = m_impl->firstSlave + static_cast<int>(j);
2707 auto* rx = m_impl->ethercatManager.getRxPDO(slave);
2708 if (rx)
2709 {
2710 rx->Controlword = 0x0000;
2711 rx->OpMode = 0;
2712 }
2713 }
2714
2715 (void)m_impl->ethercatManager.sendReceive();
2716 return false;
2717 }
2718 }
2719
2720 // ---------------------------------------------------------------------
2721 // Launch the device thread
2722 // ---------------------------------------------------------------------
2723 if (!this->start())
2724 {
2725 yCError(CIA402, "%s failed to start device thread", logPrefix);
2726 return false;
2727 }
2728
2729 yCInfo(CIA402,
2730 "%s device thread started (position strategy=%u: %s)",
2731 logPrefix,
2732 static_cast<unsigned>(desiredPositionStrategy),
2733 useSimplePidMode ? "simple PID" : "cascaded PID");
2734
2735 if (simplePidGainsAvailable)
2736 {
2737 yCInfo(CIA402, "%s simple PID gains:", logPrefix);
2738 for (size_t j = 0; j < m_impl->numAxes; ++j)
2739 {
2740 const char* axisLabel = nullptr;
2741 if (j < m_impl->variables.jointNames.size() && !m_impl->variables.jointNames[j].empty())
2742 {
2743 axisLabel = m_impl->variables.jointNames[j].c_str();
2744 }
2745
2746 const char* open = axisLabel ? " (" : "";
2747 const char* label = axisLabel ? axisLabel : "";
2748 const char* close = axisLabel ? ")" : "";
2749
2750 yCInfo(CIA402,
2751 "%s j=%zu%s%s%s Kp=%.6f Nm/deg, Kd=%.6f Nm\xC2\xB7s/deg",
2752 logPrefix,
2753 j,
2754 open,
2755 label,
2756 close,
2757 readKp[j],
2758 readKd[j]);
2759 }
2760 }
2761
2762 return true;
2763}
2764
2765// close() — stop the thread & release the NIC
2767{
2768 std::lock_guard<std::mutex> closeGuard(m_impl->CiA402MotionControlMutex);
2769 this->suspend();
2770 this->stop(); // PeriodicThread → graceful stop
2771 yCInfo(CIA402, "%s: EtheCAT master closed.", Impl::kClassName.data());
2772 return true;
2773}
2774
2775// run() — gets called every period (real-time control loop)
2776/**
2777 * Control loop phases:
2778 * 1) Apply user‑requested control modes (CiA‑402 power state machine)
2779 * 2) Push user setpoints to PDOs (units and shaft conversions handled)
2780 * 3) Cyclic exchange over EtherCAT (outputs sent / inputs read)
2781 * 4) Read back feedback (encoders, torque, safety, timestamp)
2782 * 5) Diagnostics and bookkeeping (active mode tracking, latching, inhibit)
2783 */
2785{
2786 constexpr auto logPrefix = "[run]";
2787 const auto tStart = std::chrono::steady_clock::now();
2788
2789 // lock the mutex
2790 std::lock_guard<std::mutex> runGuard(m_impl->CiA402MotionControlMutex);
2791
2792 /* ------------------------------------------------------------------
2793 * 1. APPLY USER-REQUESTED CONTROL MODES (CiA-402 power machine)
2794 * ----------------------------------------------------------------*/
2795 {
2796 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
2797
2798 for (size_t j = 0; j < m_impl->numAxes; ++j)
2799 {
2800 const int slaveIdx = m_impl->firstSlave + static_cast<int>(j);
2801 ::CiA402::RxPDO* rx = m_impl->ethercatManager.getRxPDO(slaveIdx);
2802 auto tx = m_impl->ethercatManager.getTxView(slaveIdx);
2803
2804 const int tgt = m_impl->controlModeState.target[j];
2805
2806 // If in FAULT the only way to escape from the fault is to do FORCE IDLE
2807 if (m_impl->controlModeState.active[j] == VOCAB_CM_HW_FAULT
2808 && tgt == VOCAB_CM_FORCE_IDLE)
2809 {
2810 const auto cmd = m_impl->sm[j]->faultReset(); // CW=0x0080
2811 rx->Controlword = cmd.controlword;
2812 rx->OpMode = 0; // neutral
2813 // Clear user setpoints/latches immediately
2814 m_impl->setPoints.reset((int)j);
2815 m_impl->velLatched[j] = m_impl->trqLatched[j] = m_impl->currLatched[j] = false;
2816 continue; // skip normal update-path this cycle
2817 }
2818
2819 /* ------------ normal control-mode path --------------------- */
2820 const int8_t opReq = Impl::yarpToCiaOp(tgt); // −1 = unsupported
2821 if (opReq < 0)
2822 { // ignore unknown modes
2823 continue;
2824 }
2825
2826 const bool hwInhibit = (tx.has(CiA402::TxField::STO_6621_01)
2827 && tx.get<uint8_t>(CiA402::TxField::STO_6621_01))
2829 && tx.get<uint8_t>(CiA402::TxField::SBC_6621_02));
2830 const uint16_t sw = tx.get<uint16_t>(CiA402::TxField::Statusword, 0);
2831 const int8_t od = tx.get<int8_t>(CiA402::TxField::OpModeDisplay, 0);
2832 CiA402::StateMachine::Command cmd = m_impl->sm[j]->update(sw, od, opReq, hwInhibit);
2833
2834 rx->Controlword = cmd.controlword;
2835 if (cmd.writeOpMode)
2836 {
2837 rx->OpMode = cmd.opMode;
2838 }
2839 }
2840 } /* mutex unlocked – PDOs are now ready to send */
2841
2842 /* ------------------------------------------------------------------
2843 * 2. SET USER-REQUESTED SETPOINTS (torque, position, velocity)
2844 * ----------------------------------------------------------------*/
2845 m_impl->setSetPoints();
2846
2847 /* ------------------------------------------------------------------
2848 * 3. CYCLIC EXCHANGE (send outputs / read inputs)
2849 * ----------------------------------------------------------------*/
2850 if (m_impl->ethercatManager.sendReceive() != ::CiA402::EthercatManager::Error::NoError)
2851 {
2852 yCError(CIA402,
2853 "%s sendReceive() failed, expected_wkc=%d got_wkc=%d",
2854 logPrefix,
2855 m_impl->ethercatManager.getExpectedWorkingCounter(),
2856 m_impl->ethercatManager.getWorkingCounter());
2857 m_impl->ethercatManager.dumpDiagnostics();
2858 }
2859
2860 /* ------------------------------------------------------------------
2861 * 4. COPY ENCODERS & OTHER FEEDBACK
2862 * ----------------------------------------------------------------*/
2863 m_impl->readFeedback();
2864
2865 /* ------------------------------------------------------------------
2866 * 5. DIAGNOSTICS (fill active[] according to feedback)
2867 * ----------------------------------------------------------------*/
2868 {
2869 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
2870
2871 for (size_t j = 0; j < m_impl->numAxes; ++j)
2872 {
2873 const int slaveIdx = m_impl->firstSlave + static_cast<int>(j);
2874 auto tx = m_impl->ethercatManager.getTxView(slaveIdx);
2875 bool flavourChanged = false;
2876
2877 const bool hwInhibit = (tx.has(CiA402::TxField::STO_6621_01)
2878 && tx.get<uint8_t>(CiA402::TxField::STO_6621_01))
2880 && tx.get<uint8_t>(CiA402::TxField::SBC_6621_02));
2881 const bool enabled = CiA402::StateMachine::isOperationEnabled(
2882 tx.get<uint16_t>(CiA402::TxField::Statusword, 0));
2883 const bool inFault
2886 tx.get<uint16_t>(CiA402::TxField::Statusword, 0));
2887
2888 int newActive = VOCAB_CM_IDLE;
2889 if (inFault)
2890 {
2891 newActive = VOCAB_CM_HW_FAULT;
2892 } else if (!hwInhibit && enabled)
2893 {
2894 const int activeOp = m_impl->sm[j]->getActiveOpMode();
2895 // If the drive is in CST (10), reflect the user-facing label (CURRENT or TORQUE)
2896 // that was last requested for this axis. Otherwise use the generic mapping.
2897 if (activeOp == 10)
2898 {
2899 // Guarded by the same mutex we already hold
2900 int flavor = m_impl->controlModeState.cstFlavor[j];
2901 // Safety net: constrain to CURRENT/TORQUE only
2902 if (flavor != VOCAB_CM_CURRENT && flavor != VOCAB_CM_TORQUE)
2903 {
2904 flavor = VOCAB_CM_TORQUE;
2905 }
2906 newActive = flavor;
2907
2908 // detect if the CST flavor changed since last time
2909 flavourChanged
2910 = (flavor != m_impl->controlModeState.prevCstFlavor[j])
2911 || (m_impl->controlModeState.prevCstFlavor[j] == VOCAB_CM_UNKNOWN);
2912 } else
2913 {
2914 newActive = Impl::ciaOpToYarp(activeOp);
2915 }
2916 }
2917
2918 // If IDLE or FAULT or inhibited → clear SPs and latches; force target to IDLE on HW
2919 // inhibit
2920 if (newActive == VOCAB_CM_IDLE || newActive == VOCAB_CM_HW_FAULT
2921 || newActive == VOCAB_CM_FORCE_IDLE)
2922 {
2923 m_impl->setPoints.reset(j);
2924 m_impl->velLatched[j] = m_impl->trqLatched[j] = m_impl->posLatched[j]
2925 = m_impl->currLatched[j] = false;
2926 if (hwInhibit)
2927 {
2928 m_impl->controlModeState.target[j] = VOCAB_CM_IDLE;
2929 }
2930 }
2931
2932 // Detect mode entry to (re)arm first-cycle latches
2933 if (m_impl->controlModeState.active[j] != newActive || flavourChanged)
2934 {
2935 // entering a control mode: arm latches and clear "has SP" flags
2936 m_impl->velLatched[j] = m_impl->trqLatched[j] = m_impl->posLatched[j]
2937 = m_impl->currLatched[j] = false;
2938 m_impl->setPoints.reset(j);
2939 }
2940
2941 m_impl->controlModeState.active[j] = newActive;
2942 m_impl->controlModeState.prevCstFlavor[j] = m_impl->controlModeState.cstFlavor[j];
2943 }
2944 }
2945
2946 // ---- profiling: compute per-call duration and log 30s average ----
2947 constexpr double printingIntervalSec = 30.0;
2948 const auto tEnd = std::chrono::steady_clock::now();
2949 const double dtSec
2951 m_impl->runTimeAccumSec += dtSec;
2952 m_impl->runTimeSamples += 1;
2953 const auto windowSec
2954 = std::chrono::duration_cast<std::chrono::duration<double>>(tEnd - m_impl->avgWindowStart)
2955 .count();
2956 if (windowSec >= printingIntervalSec)
2957 {
2958 const double avgMs
2959 = (m_impl->runTimeSamples > 0)
2960 ? (m_impl->runTimeAccumSec / static_cast<double>(m_impl->runTimeSamples)) * 1000.0
2961 : 0.0;
2962 yCInfoThrottle(CIA402,
2963 printingIntervalSec,
2964 "%s %.1fs window: avg run() time = %.3f ms (frequency=%.1f Hz) over %zu "
2965 "cycles (window=%.1fs) - Expected period=%.3f ms (%.1f Hz)",
2966 logPrefix,
2967 printingIntervalSec,
2968 avgMs,
2969 (m_impl->runTimeSamples > 0) ? (1000.0 / avgMs) : 0.0,
2970 m_impl->runTimeSamples,
2971 windowSec,
2972 this->getPeriod() * 1000.0,
2973 1.0 / this->getPeriod());
2974 m_impl->runTimeAccumSec = 0.0;
2975 m_impl->runTimeSamples = 0;
2976 m_impl->avgWindowStart = tEnd;
2977 }
2978}
2979
2980// -----------------------------------------------
2981// ----------------- IMotorEncoders --------------
2982// -----------------------------------------------
2983
2985{
2986 if (num == nullptr)
2987 {
2988 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
2989 return false;
2990 }
2991 *num = static_cast<int>(m_impl->numAxes);
2992 return true;
2993}
2994
2996{
2997 yCError(CIA402, "%s: resetMotorEncoder() not implemented", Impl::kClassName.data());
2998 return false;
2999}
3000
3002{
3003 yCError(CIA402, "%s: resetMotorEncoders() not implemented", Impl::kClassName.data());
3004 return false;
3005}
3006
3008{
3009 yCError(CIA402,
3010 "%s: setMotorEncoderCountsPerRevolution() not implemented",
3011 Impl::kClassName.data());
3012 return false;
3013}
3014
3015bool CiA402MotionControl::setMotorEncoder(int m, const double v)
3016{
3017 yCError(CIA402, "%s: setMotorEncoder() not implemented", Impl::kClassName.data());
3018 return false;
3019}
3020
3022{
3023 yCError(CIA402, "%s: setMotorEncoders() not implemented", Impl::kClassName.data());
3024 return false;
3025}
3026
3028{
3029 if (cpr == nullptr)
3030 {
3031 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3032 return false;
3033 }
3034 if (m >= static_cast<int>(m_impl->numAxes))
3035 {
3036 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), m);
3037 return false;
3038 }
3039
3040 {
3041 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3042
3043 // check which encoder is mounted on the motor side
3044 if (m_impl->enc1Mount[m] == Impl::Mount::Motor)
3045 *cpr = static_cast<double>(m_impl->enc1Res[m]);
3046 else if (m_impl->enc2Mount[m] == Impl::Mount::Motor)
3047 *cpr = static_cast<double>(m_impl->enc2Res[m]);
3048 else
3049 return false; // no encoder on motor side
3050 }
3051 return true;
3052}
3053
3055{
3056 if (v == nullptr)
3057 {
3058 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3059 return false;
3060 }
3061 if (m >= static_cast<int>(m_impl->numAxes))
3062 {
3063 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), m);
3064 return false;
3065 }
3066 {
3067 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3068 *v = m_impl->variables.motorEncoders[m];
3069 }
3070 return true;
3071}
3072
3074{
3075 if (encs == nullptr)
3076 {
3077 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3078 return false;
3079 }
3080 {
3081 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3082 std::memcpy(encs, m_impl->variables.motorEncoders.data(), m_impl->numAxes * sizeof(double));
3083 }
3084
3085 return true;
3086}
3087
3088bool CiA402MotionControl::getMotorEncodersTimed(double* encs, double* time)
3089{
3090 if (encs == nullptr || time == nullptr)
3091 {
3092 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3093 return false;
3094 }
3095 {
3096 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3097 std::memcpy(encs, m_impl->variables.motorEncoders.data(), m_impl->numAxes * sizeof(double));
3098 std::memcpy(time, m_impl->variables.feedbackTime.data(), m_impl->numAxes * sizeof(double));
3099 }
3100 return true;
3101}
3102
3103bool CiA402MotionControl::getMotorEncoderTimed(int m, double* encs, double* time)
3104{
3105 if (encs == nullptr || time == nullptr)
3106 {
3107 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3108 return false;
3109 }
3110 if (m >= static_cast<int>(m_impl->numAxes))
3111 {
3112 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), m);
3113 return false;
3114 }
3115 {
3116 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3117 *encs = m_impl->variables.motorEncoders[m];
3118 *time = m_impl->variables.feedbackTime[m];
3119 }
3120 return true;
3121}
3122
3124{
3125 if (sp == nullptr)
3126 {
3127 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3128 return false;
3129 }
3130 if (m >= static_cast<int>(m_impl->numAxes))
3131 {
3132 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), m);
3133 return false;
3134 }
3135 {
3136 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3137 *sp = m_impl->variables.motorVelocities[m];
3138 }
3139 return true;
3140}
3141
3143{
3144 if (spds == nullptr)
3145 {
3146 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3147 return false;
3148 }
3149 {
3150 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3151 std::memcpy(spds,
3152 m_impl->variables.motorVelocities.data(),
3153 m_impl->numAxes * sizeof(double));
3154 }
3155 return true;
3156}
3157
3159{
3160 if (acc == nullptr)
3161 {
3162 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3163 return false;
3164 }
3165 if (m >= static_cast<int>(m_impl->numAxes))
3166 {
3167 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), m);
3168 return false;
3169 }
3170 {
3171 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3172 *acc = m_impl->variables.motorAccelerations[m];
3173 }
3174 return true;
3175}
3176
3178{
3179 if (accs == nullptr)
3180 {
3181 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3182 return false;
3183 }
3184 {
3185 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3186 std::memcpy(accs,
3187 m_impl->variables.motorAccelerations.data(),
3188 m_impl->numAxes * sizeof(double));
3189 }
3190 return true;
3191}
3192
3193// -----------------------------------------------
3194// ----------------- IEncoders ------------------
3195// -----------------------------------------------
3196bool CiA402MotionControl::getEncodersTimed(double* encs, double* time)
3197{
3198 if (encs == nullptr || time == nullptr)
3199 {
3200 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3201 return false;
3202 }
3203 {
3204 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3205 std::memcpy(encs,
3206 m_impl->variables.jointPositions.data(),
3207 m_impl->numAxes * sizeof(double));
3208 std::memcpy(time, m_impl->variables.feedbackTime.data(), m_impl->numAxes * sizeof(double));
3209 }
3210 return true;
3211}
3212
3213bool CiA402MotionControl::getEncoderTimed(int j, double* encs, double* time)
3214{
3215 if (encs == nullptr || time == nullptr)
3216 {
3217 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3218 return false;
3219 }
3220 if (j >= static_cast<int>(m_impl->numAxes))
3221 {
3222 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3223 return false;
3224 }
3225 {
3226 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3227 *encs = m_impl->variables.jointPositions[j];
3228 *time = m_impl->variables.feedbackTime[j];
3229 }
3230 return true;
3231}
3232
3234{
3235 if (ax == nullptr)
3236 {
3237 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3238 return false;
3239 }
3240 *ax = static_cast<int>(m_impl->numAxes);
3241 return true;
3242}
3243
3245{
3246 yCError(CIA402, "%s: resetEncoder() not implemented", Impl::kClassName.data());
3247 return false;
3248}
3249
3251{
3252 yCError(CIA402, "%s: resetEncoders() not implemented", Impl::kClassName.data());
3253 return false;
3254}
3255
3256bool CiA402MotionControl::setEncoder(int j, const double val)
3257{
3258 yCError(CIA402, "%s: setEncoder() not implemented", Impl::kClassName.data());
3259 return false;
3260}
3261
3262bool CiA402MotionControl::setEncoders(const double* vals)
3263{
3264 yCError(CIA402, "%s: setEncoders() not implemented", Impl::kClassName.data());
3265 return false;
3266}
3267
3269{
3270 if (v == nullptr)
3271 {
3272 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3273 return false;
3274 }
3275 if (j >= static_cast<int>(m_impl->numAxes))
3276 {
3277 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3278 return false;
3279 }
3280 {
3281 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3282 *v = m_impl->variables.jointPositions[j];
3283 }
3284 return true;
3285}
3286
3288{
3289 if (encs == nullptr)
3290 {
3291 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3292 return false;
3293 }
3294 {
3295 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3296 std::memcpy(encs,
3297 m_impl->variables.jointPositions.data(),
3298 m_impl->numAxes * sizeof(double));
3299 }
3300 return true;
3301}
3302
3304{
3305 if (sp == nullptr)
3306 {
3307 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3308 return false;
3309 }
3310 if (j >= static_cast<int>(m_impl->numAxes))
3311 {
3312 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3313 return false;
3314 }
3315 {
3316 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3317 *sp = m_impl->variables.jointVelocities[j];
3318 }
3319 return true;
3320}
3321
3323{
3324 if (spds == nullptr)
3325 {
3326 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3327 return false;
3328 }
3329 {
3330 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3331 std::memcpy(spds,
3332 m_impl->variables.jointVelocities.data(),
3333 m_impl->numAxes * sizeof(double));
3334 }
3335 return true;
3336}
3337
3339{
3340 if (spds == nullptr)
3341 {
3342 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3343 return false;
3344 }
3345 if (j >= static_cast<int>(m_impl->numAxes))
3346 {
3347 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3348 return false;
3349 }
3350 {
3351 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3352 *spds = m_impl->variables.jointAccelerations[j];
3353 }
3354 return true;
3355}
3356
3358{
3359 if (accs == nullptr)
3360 {
3361 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3362 return false;
3363 }
3364 {
3365 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3366 std::memcpy(accs,
3367 m_impl->variables.jointAccelerations.data(),
3368 m_impl->numAxes * sizeof(double));
3369 }
3370 return true;
3371}
3372
3373/// -----------------------------------------------
3374/// ----------------- IAxisInfo ------------------
3375/// -----------------------------------------------
3376
3378{
3379 if (j >= static_cast<int>(m_impl->numAxes))
3380 {
3381 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3382 return false;
3383 }
3384
3385 // We assume that the name is already filled in the open() method and does not change
3386 // during the lifetime of the object. For this reason we do not need to lock the mutex
3387 // here.
3388 name = m_impl->variables.jointNames[j];
3389 return true;
3390}
3391
3392bool CiA402MotionControl::getJointType(int axis, yarp::dev::JointTypeEnum& type)
3393{
3394 if (axis >= static_cast<int>(m_impl->numAxes))
3395 {
3396 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), axis);
3397 return false;
3398 }
3399 type = yarp::dev::JointTypeEnum::VOCAB_JOINTTYPE_REVOLUTE; // TODO: add support for linear
3400 // joints
3401 return true;
3402}
3403
3404// -------------------------- IControlMode ------------------------------------
3406{
3407 if (mode == nullptr)
3408 {
3409 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3410 return false;
3411 }
3412 if (j >= static_cast<int>(m_impl->numAxes))
3413 {
3414 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3415 return false;
3416 }
3417
3418 {
3419 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
3420 *mode = m_impl->controlModeState.active[j];
3421 }
3422 return true;
3423}
3424
3426{
3427 if (modes == nullptr)
3428 {
3429 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3430 return false;
3431 }
3432
3433 {
3434 std::lock_guard<std::mutex> l(m_impl->controlModeState.mutex);
3435 std::memcpy(modes, m_impl->controlModeState.active.data(), m_impl->numAxes * sizeof(int));
3436 }
3437 return true;
3438}
3439
3440bool CiA402MotionControl::getControlModes(const int n, const int* joints, int* modes)
3441{
3442 if (modes == nullptr || joints == nullptr)
3443 {
3444 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3445 return false;
3446 }
3447 if (n <= 0)
3448 {
3449 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n);
3450 return false;
3451 }
3452
3453 {
3454 std::lock_guard<std::mutex> l(m_impl->controlModeState.mutex);
3455 for (int k = 0; k < n; ++k)
3456 {
3457 if (joints[k] >= static_cast<int>(m_impl->numAxes))
3458 {
3459 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
3460 return false;
3461 }
3462 modes[k] = m_impl->controlModeState.active[joints[k]];
3463 }
3464 }
3465 return true;
3466}
3467
3468bool CiA402MotionControl::setControlMode(const int j, const int mode)
3469{
3470 if (j >= static_cast<int>(m_impl->numAxes))
3471 {
3472 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3473 return false;
3474 }
3475 if (Impl::yarpToCiaOp(mode) < 0)
3476 {
3477 yCError(CIA402, "%s: control mode %d not supported", Impl::kClassName.data(), mode);
3478 return false;
3479 }
3480
3481 std::lock_guard<std::mutex> l(m_impl->controlModeState.mutex);
3482 m_impl->controlModeState.target[j] = mode;
3483 if (mode == VOCAB_CM_CURRENT || mode == VOCAB_CM_TORQUE)
3484 {
3485 m_impl->controlModeState.cstFlavor[j] = mode;
3486 }
3487
3488 return true;
3489}
3490
3491bool CiA402MotionControl::setControlModes(const int n, const int* joints, int* modes)
3492{
3493 if (modes == nullptr || joints == nullptr)
3494 {
3495 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3496 return false;
3497 }
3498 if (n <= 0)
3499 {
3500 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n);
3501 return false;
3502 }
3503 std::lock_guard<std::mutex> l(m_impl->controlModeState.mutex);
3504 for (int k = 0; k < n; ++k)
3505 {
3506 if (joints[k] >= static_cast<int>(m_impl->numAxes))
3507 {
3508 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
3509 return false;
3510 }
3511 m_impl->controlModeState.target[joints[k]] = modes[k];
3512
3513 if (modes[k] == VOCAB_CM_CURRENT || modes[k] == VOCAB_CM_TORQUE)
3514 {
3515 m_impl->controlModeState.cstFlavor[joints[k]] = modes[k];
3516 }
3517 }
3518 return true;
3519}
3520
3522{
3523 if (modes == nullptr)
3524 {
3525 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3526 return false;
3527 }
3528 std::lock_guard<std::mutex> l(m_impl->controlModeState.mutex);
3529 std::memcpy(m_impl->controlModeState.target.data(), modes, m_impl->numAxes * sizeof(int));
3530
3531 for (size_t j = 0; j < m_impl->numAxes; ++j)
3532 {
3533 if (m_impl->controlModeState.target[j] == VOCAB_CM_CURRENT
3534 || m_impl->controlModeState.target[j] == VOCAB_CM_TORQUE)
3535 {
3536 m_impl->controlModeState.cstFlavor[j] = m_impl->controlModeState.target[j];
3537 }
3538 }
3539
3540 return true;
3541}
3542
3543//// -------------------------- ITorqueControl ------------------------------------
3545{
3546 if (t == nullptr)
3547 {
3548 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3549 return false;
3550 }
3551 if (j >= static_cast<int>(m_impl->numAxes))
3552 {
3553 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3554 return false;
3555 }
3556 {
3557 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3558 *t = m_impl->variables.jointTorques[j];
3559 }
3560 return true;
3561}
3562
3564{
3565 if (t == nullptr)
3566 {
3567 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3568 return false;
3569 }
3570 {
3571 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
3572
3573 std::memcpy(t, m_impl->variables.jointTorques.data(), m_impl->numAxes * sizeof(double));
3574 }
3575 return true;
3576}
3577
3579{
3580 if (t == nullptr)
3581 {
3582 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3583 return false;
3584 }
3585 if (j >= static_cast<int>(m_impl->numAxes))
3586 {
3587 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3588 return false;
3589 }
3590 {
3591 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3592 *t = m_impl->setPoints.jointTorques[j];
3593 }
3594 return true;
3595}
3596
3598{
3599 if (t == nullptr)
3600 {
3601 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3602 return false;
3603 }
3604 {
3605 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3606 std::memcpy(t, m_impl->setPoints.jointTorques.data(), m_impl->numAxes * sizeof(double));
3607 }
3608 return true;
3609}
3610
3612{
3613 if (j >= static_cast<int>(m_impl->numAxes))
3614 {
3615 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3616 return false;
3617 }
3618
3619 // (a/b) Only accept if TORQUE is ACTIVE; otherwise reject (not considered)
3620 {
3621 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
3622 if (m_impl->controlModeState.active[j] != VOCAB_CM_TORQUE)
3623 {
3624 yCError(CIA402,
3625 "%s: setRefTorque rejected: TORQUE mode is not active for the joint %d",
3626 Impl::kClassName.data(),
3627 j);
3628 return false;
3629 }
3630 }
3631
3632 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3633 m_impl->setPoints.jointTorques[j] = t;
3634 m_impl->setPoints.hasTorqueSP[j] = true; // (b)
3635 return true;
3636}
3637
3639{
3640 if (t == nullptr)
3641 {
3642 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3643 return false;
3644 }
3645 {
3646 // check that all the joints are in TORQUE mode use std function without for loop
3647 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
3648 for (size_t j = 0; j < m_impl->numAxes; ++j)
3649 {
3650 if (m_impl->controlModeState.active[j] != VOCAB_CM_TORQUE)
3651 {
3652 yCError(CIA402,
3653 "%s: setRefTorques rejected: TORQUE mode is not active for the joint "
3654 "%zu",
3655 Impl::kClassName.data(),
3656 j);
3657 return false; // reject
3658 }
3659 }
3660 }
3661
3662 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3663 std::memcpy(m_impl->setPoints.jointTorques.data(), t, m_impl->numAxes * sizeof(double));
3664 std::fill(m_impl->setPoints.hasTorqueSP.begin(), m_impl->setPoints.hasTorqueSP.end(), true);
3665 return true;
3666}
3667
3668bool CiA402MotionControl::setRefTorques(const int n_joint, const int* joints, const double* t)
3669{
3670 if (t == nullptr || joints == nullptr)
3671 {
3672 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3673 return false;
3674 }
3675 if (n_joint <= 0)
3676 {
3677 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n_joint);
3678 return false;
3679 }
3680
3681 // check that all the joints are in TORQUE mode
3682 {
3683 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
3684 for (int k = 0; k < n_joint; ++k)
3685 {
3686 if (joints[k] >= static_cast<int>(m_impl->numAxes))
3687 {
3688 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
3689 return false;
3690 }
3691 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_TORQUE)
3692 {
3693 yCError(CIA402,
3694 "%s: setRefTorques rejected: TORQUE mode is not active for the joint %d",
3695 Impl::kClassName.data(),
3696 joints[k]);
3697 return false; // reject
3698 }
3699 }
3700 }
3701
3702 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3703 for (int k = 0; k < n_joint; ++k)
3704 {
3705 m_impl->setPoints.jointTorques[joints[k]] = t[k];
3706 m_impl->setPoints.hasTorqueSP[joints[k]] = true;
3707 }
3708 return true;
3709}
3710
3711bool CiA402MotionControl::getTorqueRange(int j, double* min, double* max)
3712{
3713 if (min == nullptr || max == nullptr)
3714 {
3715 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3716 return false;
3717 }
3718 if (j >= static_cast<int>(m_impl->numAxes))
3719 {
3720 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3721 return false;
3722 }
3723
3724 // multiply by the transmission ratio to convert motor torque to joint torque
3725 *min = -m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3726 *max = m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3727
3728 return true;
3729}
3730
3731bool CiA402MotionControl::getTorqueRanges(double* min, double* max)
3732{
3733 if (min == nullptr || max == nullptr)
3734 {
3735 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3736 return false;
3737 }
3738
3739 for (size_t j = 0; j < m_impl->numAxes; ++j)
3740 {
3741 min[j] = -m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3742 max[j] = m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3743 }
3744 return true;
3745}
3746
3748{
3749 if (j >= static_cast<int>(m_impl->numAxes))
3750 {
3751 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3752 return false;
3753 }
3754
3755 // (a/b) Only accept if VELOCITY is ACTIVE; otherwise reject
3756 {
3757 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
3758 if (m_impl->controlModeState.active[j] != VOCAB_CM_VELOCITY)
3759 {
3760 yCError(CIA402,
3761 "%s: velocityMove rejected: VELOCITY mode is not active for the joint %d",
3762 Impl::kClassName.data(),
3763 j);
3764
3765 // this will return true to indicate the rejection was handled
3766 return true;
3767 }
3768 }
3769
3770 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3771 m_impl->setPoints.jointVelocities[j] = spd;
3772 m_impl->setPoints.hasVelSP[j] = true; // (b)
3773 return true;
3774}
3775
3777{
3778 if (spds == nullptr)
3779 {
3780 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3781 return false;
3782 }
3783
3784 // check that all the joints are in VELOCITY mode
3785 {
3786 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
3787 for (size_t j = 0; j < m_impl->numAxes; ++j)
3788 {
3789 if (m_impl->controlModeState.active[j] != VOCAB_CM_VELOCITY)
3790 {
3791 yCError(CIA402,
3792 "%s: velocityMove rejected: VELOCITY mode is not active for the joint "
3793 "%zu",
3794 Impl::kClassName.data(),
3795 j);
3796 return false; // reject
3797 }
3798 }
3799 }
3800
3801 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3802 std::memcpy(m_impl->setPoints.jointVelocities.data(), spds, m_impl->numAxes * sizeof(double));
3803 std::fill(m_impl->setPoints.hasVelSP.begin(), m_impl->setPoints.hasVelSP.end(), true);
3804 return true;
3805}
3806
3807bool CiA402MotionControl::getRefVelocity(const int joint, double* vel)
3808{
3809 if (vel == nullptr)
3810 {
3811 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3812 return false;
3813 }
3814 if (joint >= static_cast<int>(m_impl->numAxes))
3815 {
3816 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joint);
3817 return false;
3818 }
3819 {
3820 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3821 *vel = m_impl->setPoints.jointVelocities[joint];
3822 }
3823 return true;
3824}
3825
3827{
3828 if (spds == nullptr)
3829 {
3830 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3831 return false;
3832 }
3833 {
3834 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3835 std::memcpy(spds,
3836 m_impl->setPoints.jointVelocities.data(),
3837 m_impl->numAxes * sizeof(double));
3838 }
3839 return true;
3840}
3841
3842bool CiA402MotionControl::getRefVelocities(const int n_joint, const int* joints, double* vels)
3843{
3844 if (vels == nullptr || joints == nullptr)
3845 {
3846 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3847 return false;
3848 }
3849 if (n_joint <= 0)
3850 {
3851 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n_joint);
3852 return false;
3853 }
3854
3855 {
3856 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
3857 for (int k = 0; k < n_joint; ++k)
3858 {
3859 if (joints[k] >= static_cast<int>(m_impl->numAxes))
3860 {
3861 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
3862 return false;
3863 }
3864 vels[k] = m_impl->setPoints.jointVelocities[joints[k]];
3865 }
3866 }
3867 return true;
3868}
3869
3870// Acceleration is expressed in YARP joint units [deg/s^2].
3871// For PP we SDO-write 0x6083/0x6084/0x6085 in rpm/s (deg/s^2 ÷ 6).
3872// For CSV we just cache the value (no standard accel SDO in CSV).
3873
3875{
3876 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
3877 {
3878 yCError(CIA402, "%s: setRefAcceleration: joint %d out of range", Impl::kClassName.data(), j);
3879 return false;
3880 }
3881
3882 // store magnitude
3883 if (accDegS2 < 0.0)
3884 {
3885 accDegS2 = -accDegS2;
3886 }
3887
3888 // saturate to maximum allowed 10 deg/s^2
3889 constexpr double maxAcc = 10.0;
3890 if (accDegS2 > maxAcc)
3891 {
3892 yCWarning(CIA402,
3893 "%s: setRefAcceleration: joint %d: acceleration %.2f deg/s^2 too high, "
3894 "saturating to %.2f deg/s^2",
3895 Impl::kClassName.data(),
3896 j,
3897 accDegS2,
3898 maxAcc);
3899 accDegS2 = maxAcc;
3900 }
3901
3902 // Only touch SDOs if PP is ACTIVE
3903 int controlMode = -1;
3904 {
3905 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
3906 controlMode = m_impl->controlModeState.active[j];
3907 }
3908
3909 if (controlMode != VOCAB_CM_POSITION)
3910 {
3911 // do nothing if not in PP
3912 return true;
3913 }
3914
3915 const int s = m_impl->firstSlave + j;
3916 const int32_t acc = static_cast<int32_t>(std::llround(accDegS2 * m_impl->degSToVel[j]));
3917 {
3918 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
3919 m_impl->ppState.ppRefAccelerationDegSS[j] = accDegS2;
3920 }
3921
3922 // Profile acceleration / deceleration / quick-stop deceleration
3923 (void)m_impl->ethercatManager.writeSDO<int32_t>(s, 0x6083, 0x00, acc);
3924 (void)m_impl->ethercatManager.writeSDO<int32_t>(s, 0x6084, 0x00, acc);
3925 (void)m_impl->ethercatManager.writeSDO<int32_t>(s, 0x6085, 0x00, acc);
3926
3927 return true;
3928}
3929
3930bool CiA402MotionControl::setRefAccelerations(const double* accsDegS2)
3931{
3932 if (!accsDegS2)
3933 {
3934 yCError(CIA402, "%s: setRefAccelerations: null pointer", Impl::kClassName.data());
3935 return false;
3936 }
3937 bool ok = true;
3938 for (size_t j = 0; j < m_impl->numAxes; ++j)
3939 {
3940 ok = setRefAcceleration(static_cast<int>(j), accsDegS2[j]) && ok;
3941 }
3942 return ok;
3943}
3944
3946{
3947 if (acc == nullptr)
3948 {
3949 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3950 return false;
3951 }
3952 if (j >= static_cast<int>(m_impl->numAxes))
3953 {
3954 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), j);
3955 return false;
3956 }
3957
3958 int controlMode = -1;
3959 {
3960 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
3961 controlMode = m_impl->controlModeState.active[j];
3962 }
3963
3964 if (controlMode == VOCAB_CM_POSITION)
3965 {
3966 // if in PP return the cached value
3967 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
3968 *acc = m_impl->ppState.ppRefAccelerationDegSS[j];
3969 return true;
3970 }
3971
3972 *acc = 0.0;
3973 return true;
3974}
3975
3977{
3978 if (accs == nullptr)
3979 {
3980 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
3981 return false;
3982 }
3983
3984 for (size_t j = 0; j < m_impl->numAxes; ++j)
3985 {
3986 int controlMode = -1;
3987 {
3988 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
3989 controlMode = m_impl->controlModeState.active[j];
3990 }
3991
3992 if (controlMode == VOCAB_CM_POSITION)
3993 {
3994 // if in PP return the cached value
3995 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
3996 accs[j] = m_impl->ppState.ppRefAccelerationDegSS[j];
3997 } else
3998 {
3999 accs[j] = 0.0;
4000 }
4001 }
4002 return true;
4003}
4004
4005// stop() semantics:
4006// • PP → set CW bit 8 (HALT), decelerating with 0x6084.
4007// • CSV/others → zero TargetVelocity (current behavior kept).
4008
4010{
4011 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4012 {
4013 yCError(CIA402, "%s: stop: joint %d out of range", Impl::kClassName.data(), j);
4014 return false;
4015 }
4016
4017 int controlMode = -1;
4018 {
4019 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4020 controlMode = m_impl->controlModeState.active[j];
4021 }
4022
4023 if (controlMode == VOCAB_CM_POSITION)
4024 {
4025 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4026 m_impl->ppState.ppHaltRequested[j] = true; // consumed in setSetPoints()
4027 return true;
4028 }
4029
4030 // CSV/others → zero velocity set-point
4031 {
4032 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4033 m_impl->setPoints.jointVelocities[j] = 0.0;
4034 m_impl->setPoints.hasVelSP[j] = true;
4035 }
4036 return true;
4037}
4038
4040{
4041 // PP axes → HALT; non-PP axes → velocity 0
4042 {
4043 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4044 for (size_t j = 0; j < m_impl->numAxes; ++j)
4045 {
4046 if (m_impl->controlModeState.active[j] == VOCAB_CM_POSITION)
4047 {
4048 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4049 m_impl->ppState.ppHaltRequested[j] = true;
4050 }
4051 }
4052 }
4053 {
4054 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4055 std::fill(m_impl->setPoints.jointVelocities.begin(),
4056 m_impl->setPoints.jointVelocities.end(),
4057 0.0);
4058 std::fill(m_impl->setPoints.hasVelSP.begin(), m_impl->setPoints.hasVelSP.end(), true);
4059 }
4060 return true;
4061}
4062
4063bool CiA402MotionControl::velocityMove(const int n_joint, const int* joints, const double* spds)
4064{
4065 if (spds == nullptr || joints == nullptr)
4066 {
4067 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4068 return false;
4069 }
4070 if (n_joint <= 0)
4071 {
4072 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n_joint);
4073 return false;
4074 }
4075
4076 // check that all the joints are in VELOCITY mode
4077 {
4078 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
4079 for (int k = 0; k < n_joint; ++k)
4080 {
4081 if (joints[k] >= static_cast<int>(m_impl->numAxes))
4082 {
4083 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
4084 return false;
4085 }
4086 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_VELOCITY)
4087 {
4088 yCError(CIA402,
4089 "%s: velocityMove rejected: VELOCITY mode is not active for the joint "
4090 "%d",
4091 Impl::kClassName.data(),
4092 joints[k]);
4093 return false; // reject
4094 }
4095 }
4096 }
4097
4098 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4099 for (int k = 0; k < n_joint; ++k)
4100 {
4101 m_impl->setPoints.jointVelocities[joints[k]] = spds[k];
4102 m_impl->setPoints.hasVelSP[joints[k]] = true;
4103 }
4104
4105 return true;
4106}
4107
4109 const int* joints,
4110 const double* accs)
4111{
4112 if (accs == nullptr || joints == nullptr)
4113 {
4114 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4115 return false;
4116 }
4117 if (n_joint <= 0)
4118 {
4119 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n_joint);
4120 return false;
4121 }
4122
4123 // no operation
4124 return true;
4125}
4126
4127bool CiA402MotionControl::getRefAccelerations(const int n_joint, const int* joints, double* accs)
4128{
4129 if (accs == nullptr || joints == nullptr)
4130 {
4131 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4132 return false;
4133 }
4134 std::memset(accs, 0, n_joint * sizeof(double)); // CiA-402 does not support acceleration
4135 // setpoints, so we return 0.0 for all axes
4136 return true;
4137}
4138
4139bool CiA402MotionControl::stop(const int n_joint, const int* joints)
4140{
4141 if (joints == nullptr)
4142 {
4143 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4144 return false;
4145 }
4146 if (n_joint <= 0)
4147 {
4148 yCError(CIA402, "%s: invalid number of joints %d", Impl::kClassName.data(), n_joint);
4149 return false;
4150 }
4151
4152 {
4153 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4154 for (int k = 0; k < n_joint; ++k)
4155 {
4156 if (joints[k] >= static_cast<int>(m_impl->numAxes))
4157 {
4158 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
4159 return false;
4160 }
4161 m_impl->setPoints.jointVelocities[joints[k]] = 0.0;
4162 m_impl->setPoints.hasVelSP[joints[k]] = true;
4163 }
4164 }
4165 return true;
4166}
4167
4169{
4170 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4171 {
4172 yCError(CIA402, "%s: getLastJointFault: joint %d out of range", Impl::kClassName.data(), j);
4173 return false;
4174 }
4175
4176 const int slave = m_impl->firstSlave + j;
4177
4178 // --- 0x603F:00 Error code (UINT16) ---
4179 uint16_t code = 0;
4180 auto err = m_impl->ethercatManager.readSDO<uint16_t>(slave, 0x603F, 0x00, code);
4182 {
4183 yCError(CIA402,
4184 "%s: getLastJointFault: SDO read 0x603F:00 failed (joint %d)",
4185 Impl::kClassName.data(),
4186 j);
4187 return false;
4188 }
4189
4190 fault = static_cast<int>(code);
4191 message = m_impl->describe603F(code);
4192
4193 // --- 0x203F:01 Error report (STRING(8)) ---
4194 // Use a fixed char[8] so we can call the templated readSDO<T> unmodified.
4195 char report[8] = {0}; // zero-init so partial reads are safely NUL-terminated
4196 auto err2 = m_impl->ethercatManager.readSDO(slave, 0x203F, 0x01, report);
4198 {
4199 // Trim at first NUL (STRING(8) is not guaranteed to be fully used)
4200 std::size_t len = 0;
4201 while (len < sizeof(report) && report[len] != '\0')
4202 ++len;
4203
4204 if (len > 0)
4205 {
4206 // If it's clean printable ASCII, append as text; otherwise show hex bytes.
4207 bool printable = true;
4208 for (std::size_t i = 0; i < len; ++i)
4209 {
4210 const unsigned char c = static_cast<unsigned char>(report[i]);
4211 if (c < 0x20 || c > 0x7E)
4212 {
4213 printable = false;
4214 break;
4215 }
4216 }
4217
4218 if (printable)
4219 {
4220 message += " — report: ";
4221 message.append(report, len);
4222 } else
4223 {
4224 char hex[3 * 8 + 1] = {0};
4225 int pos = 0;
4226 for (std::size_t i = 0; i < len && pos <= static_cast<int>(sizeof(hex)) - 3; ++i)
4227 pos += std::snprintf(hex + pos,
4228 sizeof(hex) - pos,
4229 "%02X%s",
4230 static_cast<unsigned char>(report[i]),
4231 (i + 1 < len) ? " " : "");
4232 message += " — report: [";
4233 message += hex;
4234 message += "]";
4235 }
4236 }
4237 }
4238 return true;
4239}
4240
4241bool CiA402MotionControl::positionMove(int j, double refDeg)
4242{
4243 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4244 {
4245 yCError(CIA402, "%s: positionMove: joint %d out of range", Impl::kClassName.data(), j);
4246 return false;
4247 }
4248 // accept only if PP is ACTIVE (same policy as your CSV path)
4249 int controlMode = -1;
4250 {
4251 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4252 controlMode = m_impl->controlModeState.active[j];
4253 }
4254
4255 if (controlMode != VOCAB_CM_POSITION)
4256 {
4257 yCError(CIA402,
4258 "%s: positionMove rejected: POSITION mode not active for joint %d",
4259 Impl::kClassName.data(),
4260 j);
4261 return false;
4262 }
4263
4264 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4265 m_impl->setPoints.ppJointTargetsDeg[j] = refDeg;
4266 m_impl->setPoints.ppTargetCounts[j] = m_impl->jointDegToTargetCounts(size_t(j), refDeg);
4267 m_impl->setPoints.ppIsRelative[j] = false;
4268 m_impl->setPoints.ppHasPosSP[j] = true;
4269 m_impl->setPoints.ppPulseHi[j] = true; // schedule rising edge on CW bit4
4270 return true;
4271}
4272
4273bool CiA402MotionControl::positionMove(const double* refsDeg)
4274{
4275 if (!refsDeg)
4276 {
4277 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4278 return false;
4279 }
4280
4281 // all axes must be in PP
4282 {
4283 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4284 for (size_t j = 0; j < m_impl->numAxes; ++j)
4285 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4286 {
4287 yCError(CIA402,
4288 "%s: positionMove rejected: POSITION mode not active on joint %zu",
4289 Impl::kClassName.data(),
4290 j);
4291 return false;
4292 }
4293 }
4294
4295 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4296 for (size_t j = 0; j < m_impl->numAxes; ++j)
4297 {
4298 m_impl->setPoints.ppJointTargetsDeg[j] = refsDeg[j];
4299 m_impl->setPoints.ppTargetCounts[j] = m_impl->jointDegToTargetCounts(j, refsDeg[j]);
4300 m_impl->setPoints.ppIsRelative[j] = false;
4301 m_impl->setPoints.ppHasPosSP[j] = true;
4302 m_impl->setPoints.ppPulseHi[j] = true;
4303 }
4304 return true;
4305}
4306
4307bool CiA402MotionControl::positionMove(const int n, const int* joints, const double* refsDeg)
4308{
4309 if (!joints || !refsDeg || n <= 0)
4310 {
4311 yCError(CIA402, "%s: invalid args", Impl::kClassName.data());
4312 return false;
4313 }
4314 {
4315 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4316 for (int k = 0; k < n; ++k)
4317 {
4318 if (joints[k] < 0 || joints[k] >= static_cast<int>(m_impl->numAxes))
4319 return false;
4320 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION)
4321 {
4322 yCError(CIA402,
4323 "%s: positionMove rejected: POSITION mode not active on joint %d",
4324 Impl::kClassName.data(),
4325 joints[k]);
4326 return false;
4327 }
4328 }
4329 }
4330 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4331 for (int k = 0; k < n; ++k)
4332 {
4333 const int j = joints[k];
4334 m_impl->setPoints.ppJointTargetsDeg[j] = refsDeg[k];
4335 m_impl->setPoints.ppTargetCounts[j] = m_impl->jointDegToTargetCounts(size_t(j), refsDeg[k]);
4336 m_impl->setPoints.ppIsRelative[j] = false;
4337 m_impl->setPoints.ppHasPosSP[j] = true;
4338 m_impl->setPoints.ppPulseHi[j] = true;
4339 }
4340 return true;
4341}
4342
4343bool CiA402MotionControl::relativeMove(int j, double deltaDeg)
4344{
4345 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4346 return false;
4347 {
4348 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4349 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4350 {
4351 yCError(CIA402,
4352 "%s: relativeMove rejected: POSITION mode not active for joint %d",
4353 Impl::kClassName.data(),
4354 j);
4355 return true;
4356 }
4357 }
4358 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4359 m_impl->setPoints.ppJointTargetsDeg[j] += deltaDeg; // cache last target in deg
4360 m_impl->setPoints.ppTargetCounts[j] = m_impl->jointDegToTargetCounts(size_t(j), deltaDeg);
4361 m_impl->setPoints.ppIsRelative[j] = true;
4362 m_impl->setPoints.ppHasPosSP[j] = true;
4363 m_impl->setPoints.ppPulseHi[j] = true;
4364 return true;
4365}
4366
4367bool CiA402MotionControl::relativeMove(const double* deltasDeg)
4368{
4369 if (!deltasDeg)
4370 return false;
4371 {
4372 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4373 for (size_t j = 0; j < m_impl->numAxes; ++j)
4374 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4375 return false;
4376 }
4377 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4378 for (size_t j = 0; j < m_impl->numAxes; ++j)
4379 {
4380 m_impl->setPoints.ppJointTargetsDeg[j] += deltasDeg[j];
4381 m_impl->setPoints.ppTargetCounts[j] = m_impl->jointDegToTargetCounts(j, deltasDeg[j]);
4382 m_impl->setPoints.ppIsRelative[j] = true;
4383 m_impl->setPoints.ppHasPosSP[j] = true;
4384 m_impl->setPoints.ppPulseHi[j] = true;
4385 }
4386 return true;
4387}
4388
4389bool CiA402MotionControl::relativeMove(const int n, const int* joints, const double* deltasDeg)
4390{
4391 if (!joints || !deltasDeg || n <= 0)
4392 return false;
4393 {
4394 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4395 for (int k = 0; k < n; ++k)
4396 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION)
4397 return false;
4398 }
4399 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4400 for (int k = 0; k < n; ++k)
4401 {
4402 const int j = joints[k];
4403 m_impl->setPoints.ppJointTargetsDeg[j] += deltasDeg[k];
4404 m_impl->setPoints.ppTargetCounts[j]
4405 = m_impl->jointDegToTargetCounts(size_t(j), deltasDeg[k]);
4406 m_impl->setPoints.ppIsRelative[j] = true;
4407 m_impl->setPoints.ppHasPosSP[j] = true;
4408 m_impl->setPoints.ppPulseHi[j] = true;
4409 }
4410 return true;
4411}
4412
4414{
4415 if (flag == nullptr)
4416 {
4417 yCError(CIA402, "%s: checkMotionDone: null pointer", Impl::kClassName.data());
4418 return false;
4419 }
4420
4421 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4422 {
4423 yCError(CIA402, "%s: checkMotionDone: joint %d out of range", Impl::kClassName.data(), j);
4424 return false;
4425 }
4426
4427 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4428 *flag = m_impl->variables.targetReached[j];
4429 return true;
4430}
4431
4433{
4434 if (flag == nullptr)
4435 {
4436 yCError(CIA402, "%s: checkMotionDone: null pointer", Impl::kClassName.data());
4437 return false;
4438 }
4439
4440 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4441 for (size_t j = 0; j < m_impl->numAxes; ++j)
4442 {
4443 flag[j] = m_impl->variables.targetReached[j];
4444 }
4445
4446 return true;
4447}
4448
4449bool CiA402MotionControl::checkMotionDone(const int n, const int* joints, bool* flag)
4450{
4451 if (!joints || !flag || n <= 0)
4452 return false;
4453 bool all = true;
4454 for (int k = 0; k < n; ++k)
4455 {
4456 bool f = true;
4457 checkMotionDone(joints[k], &f);
4458 all = all && f;
4459 }
4460 *flag = all;
4461 return true;
4462}
4463
4464bool CiA402MotionControl::setRefSpeed(int j, double spDegS)
4465{
4466 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4467 {
4468 yCError(CIA402, "%s: setRefSpeed: joint %d out of range", Impl::kClassName.data(), j);
4469 return false;
4470 }
4471
4472 // Only write SDO if PP is active (current behavior)
4473 int cm = -1;
4474 {
4475 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4476 cm = m_impl->controlModeState.active[j];
4477 }
4478 if (cm != VOCAB_CM_POSITION)
4479 {
4480 yCError(CIA402,
4481 "%s: setRefSpeed: POSITION mode not active for joint %d, not writing SDO",
4482 Impl::kClassName.data(),
4483 j);
4484 return true;
4485 }
4486
4487 // Cache for getRefSpeed()
4488 {
4489 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4490 m_impl->ppState.ppRefSpeedDegS[j] = spDegS;
4491 }
4492
4493 m_impl->setSDORefSpeed(j, spDegS);
4494
4495 return true;
4496}
4497
4498bool CiA402MotionControl::setRefSpeeds(const double* spDegS)
4499{
4500 if (spDegS == nullptr)
4501 {
4502 yCError(CIA402, "%s: setRefSpeeds: null pointer", Impl::kClassName.data());
4503 return false;
4504 }
4505 for (size_t j = 0; j < m_impl->numAxes; ++j)
4506 {
4507 this->setRefSpeed(static_cast<int>(j), spDegS[j]);
4508 }
4509 return true;
4510}
4511
4512bool CiA402MotionControl::setRefSpeeds(const int n, const int* joints, const double* spDegS)
4513{
4514 if (!joints || !spDegS || n <= 0)
4515 {
4516 yCError(CIA402, "%s: setRefSpeeds: invalid args", Impl::kClassName.data());
4517 return false;
4518 }
4519
4520 for (int k = 0; k < n; ++k)
4521 {
4522 this->setRefSpeed(joints[k], spDegS[k]);
4523 }
4524 return true;
4525}
4526
4527bool CiA402MotionControl::getRefSpeed(int j, double* ref)
4528{
4529 if (!ref || j < 0 || j >= static_cast<int>(m_impl->numAxes))
4530 {
4531 yCError(CIA402, "%s: getRefSpeed: invalid args", Impl::kClassName.data());
4532 return false;
4533 }
4534
4535 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4536 *ref = m_impl->ppState.ppRefSpeedDegS[j];
4537 return true;
4538}
4540{
4541 if (!spds)
4542 {
4543 yCError(CIA402, "%s: getRefSpeeds: null pointer", Impl::kClassName.data());
4544 return false;
4545 }
4546 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4547 std::memcpy(spds, m_impl->ppState.ppRefSpeedDegS.data(), m_impl->numAxes * sizeof(double));
4548 return true;
4549}
4550
4551bool CiA402MotionControl::getRefSpeeds(const int n, const int* joints, double* spds)
4552{
4553 if (!joints || !spds || n <= 0)
4554 {
4555 yCError(CIA402, "%s: getRefSpeeds: invalid args", Impl::kClassName.data());
4556 return false;
4557 }
4558 std::lock_guard<std::mutex> lock(m_impl->ppState.mutex);
4559 for (int k = 0; k < n; ++k)
4560 {
4561 spds[k] = m_impl->ppState.ppRefSpeedDegS[joints[k]];
4562 }
4563 return true;
4564}
4565
4566bool CiA402MotionControl::getTargetPosition(const int j, double* ref)
4567{
4568 if (!ref || j < 0 || j >= static_cast<int>(m_impl->numAxes))
4569 {
4570 yCError(CIA402, "%s: getTargetPosition: invalid args", Impl::kClassName.data());
4571 return false;
4572 }
4573
4574 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4575 *ref = m_impl->setPoints.ppJointTargetsDeg[j];
4576 return true;
4577}
4578
4580{
4581 if (refs == nullptr)
4582 {
4583 yCError(CIA402, "%s: getTargetPositions: null pointer", Impl::kClassName.data());
4584 return false;
4585 }
4586
4587 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4588 std::memcpy(refs, m_impl->setPoints.ppJointTargetsDeg.data(), m_impl->numAxes * sizeof(double));
4589 return true;
4590}
4591
4592bool CiA402MotionControl::getTargetPositions(const int n, const int* joints, double* refs)
4593{
4594 if (!joints || !refs || n <= 0)
4595 {
4596 yCError(CIA402, "%s: getTargetPositions: invalid args", Impl::kClassName.data());
4597 return false;
4598 }
4599 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4600 for (int k = 0; k < n; ++k)
4601 {
4602 refs[k] = m_impl->setPoints.ppJointTargetsDeg[joints[k]];
4603 }
4604 return true;
4605}
4606
4607// ---------------- IPositionDirect --------------
4608
4609bool CiA402MotionControl::setPosition(int j, double refDeg)
4610{
4611 if (j < 0 || j >= static_cast<int>(m_impl->numAxes))
4612 {
4613 yCError(CIA402, "%s: setPosition: joint %d out of range", Impl::kClassName.data(), j);
4614 return false;
4615 }
4616
4617 {
4618 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4619 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION_DIRECT)
4620 {
4621 yCError(CIA402,
4622 "%s: setPosition rejected: POSITION_DIRECT mode is not active for joint %d",
4623 Impl::kClassName.data(),
4624 j);
4625 return false;
4626 }
4627 }
4628
4629 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4630 m_impl->setPoints.positionDirectJointTargetsDeg[j] = refDeg;
4631 m_impl->setPoints.positionDirectTargetCounts[j]
4632 = m_impl->jointDegToTargetCounts(static_cast<size_t>(j), refDeg);
4633 return true;
4634}
4635
4637{
4638 if (refs == nullptr)
4639 {
4640 yCError(CIA402, "%s: setPositions: null pointer", Impl::kClassName.data());
4641 return false;
4642 }
4643
4644 {
4645 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
4646 for (size_t j = 0; j < m_impl->numAxes; ++j)
4647 {
4648 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION_DIRECT)
4649 {
4650 yCError(CIA402,
4651 "%s: setPositions rejected: POSITION_DIRECT mode is not active for joint "
4652 "%zu",
4653 Impl::kClassName.data(),
4654 j);
4655 return false;
4656 }
4657 }
4658 }
4659
4660 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4661 for (size_t j = 0; j < m_impl->numAxes; ++j)
4662 {
4663 m_impl->setPoints.positionDirectJointTargetsDeg[j] = refs[j];
4664 m_impl->setPoints.positionDirectTargetCounts[j]
4665 = m_impl->jointDegToTargetCounts(j, refs[j]);
4666 }
4667 return true;
4668}
4669
4670bool CiA402MotionControl::setPositions(const int n_joint, const int* joints, const double* refs)
4671{
4672 if (!joints || !refs)
4673 {
4674 yCError(CIA402, "%s: setPositions: null pointer", Impl::kClassName.data());
4675 return false;
4676 }
4677 if (n_joint <= 0)
4678 {
4679 yCError(CIA402,
4680 "%s: setPositions: invalid number of joints %d",
4681 Impl::kClassName.data(),
4682 n_joint);
4683 return false;
4684 }
4685
4686 {
4687 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
4688 for (int k = 0; k < n_joint; ++k)
4689 {
4690 if (joints[k] < 0 || joints[k] >= static_cast<int>(m_impl->numAxes))
4691 {
4692 yCError(CIA402,
4693 "%s: setPositions: joint %d out of range",
4694 Impl::kClassName.data(),
4695 joints[k]);
4696 return false;
4697 }
4698 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION_DIRECT)
4699 {
4700 yCError(CIA402,
4701 "%s: setPositions rejected: POSITION_DIRECT mode is not active for joint "
4702 "%d",
4703 Impl::kClassName.data(),
4704 joints[k]);
4705 return false;
4706 }
4707 }
4708 }
4709
4710 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4711 for (int k = 0; k < n_joint; ++k)
4712 {
4713 const int j = joints[k];
4714 m_impl->setPoints.positionDirectJointTargetsDeg[j] = refs[k];
4715 m_impl->setPoints.positionDirectTargetCounts[j]
4716 = m_impl->jointDegToTargetCounts(static_cast<size_t>(j), refs[k]);
4717 }
4718 return true;
4719}
4720
4721bool CiA402MotionControl::getRefPosition(const int joint, double* ref)
4722{
4723 if (!ref)
4724 {
4725 yCError(CIA402, "%s: getRefPosition: null pointer", Impl::kClassName.data());
4726 return false;
4727 }
4728 if (joint < 0 || joint >= static_cast<int>(m_impl->numAxes))
4729 {
4730 yCError(CIA402, "%s: getRefPosition: joint %d out of range", Impl::kClassName.data(), joint);
4731 return false;
4732 }
4733
4734 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4735 *ref = m_impl->setPoints.positionDirectJointTargetsDeg[joint];
4736 return true;
4737}
4738
4740{
4741 if (!refs)
4742 {
4743 yCError(CIA402, "%s: getRefPositions: null pointer", Impl::kClassName.data());
4744 return false;
4745 }
4746
4747 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4748 std::memcpy(refs,
4749 m_impl->setPoints.positionDirectJointTargetsDeg.data(),
4750 m_impl->numAxes * sizeof(double));
4751 return true;
4752}
4753
4754bool CiA402MotionControl::getRefPositions(const int n_joint, const int* joints, double* refs)
4755{
4756 if (!joints || !refs)
4757 {
4758 yCError(CIA402, "%s: getRefPositions: null pointer", Impl::kClassName.data());
4759 return false;
4760 }
4761 if (n_joint <= 0)
4762 {
4763 yCError(CIA402,
4764 "%s: getRefPositions: invalid number of joints %d",
4765 Impl::kClassName.data(),
4766 n_joint);
4767 return false;
4768 }
4769
4770 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4771 for (int k = 0; k < n_joint; ++k)
4772 {
4773 if (joints[k] < 0 || joints[k] >= static_cast<int>(m_impl->numAxes))
4774 {
4775 yCError(CIA402,
4776 "%s: getRefPositions: joint %d out of range",
4777 Impl::kClassName.data(),
4778 joints[k]);
4779 return false;
4780 }
4781 refs[k] = m_impl->setPoints.positionDirectJointTargetsDeg[joints[k]];
4782 }
4783 return true;
4784}
4785
4787{
4788 if (!num)
4789 {
4790 yCError(CIA402, "%s: getNumberOfMotors: null pointer", Impl::kClassName.data());
4791 return false;
4792 }
4793 *num = m_impl->numAxes;
4794 return true;
4795}
4796
4798{
4799 if (val == nullptr)
4800 {
4801 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4802 return false;
4803 }
4804 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
4805 {
4806 yCError(CIA402, "%s: motor %d out of range", Impl::kClassName.data(), m);
4807 return false;
4808 }
4809 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4810 *val = m_impl->variables.driveTemperatures[m];
4811 return true;
4812}
4813
4815{
4816 if (vals == nullptr)
4817 {
4818 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4819 return false;
4820 }
4821 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4822 std::memcpy(vals, m_impl->variables.driveTemperatures.data(), m_impl->numAxes * sizeof(double));
4823 return true;
4824}
4825
4827{
4828 // The get temperature limit function is not implemented
4829 yCError(CIA402,
4830 "%s: The getTemperatureLimit function is not implemented",
4831 Impl::kClassName.data());
4832 return false;
4833}
4834
4835bool CiA402MotionControl::setTemperatureLimit(int m, const double temp)
4836{
4837 // The set temperature limit function is not implemented
4838 yCError(CIA402,
4839 "%s: The setTemperatureLimit function is not implemented",
4840 Impl::kClassName.data());
4841 return false;
4842}
4843
4845{
4846 if (val == nullptr)
4847 {
4848 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
4849 return false;
4850 }
4851 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
4852 {
4853 yCError(CIA402, "%s: motor %d out of range", Impl::kClassName.data(), m);
4854 return false;
4855 }
4856 *val = m_impl->gearRatio[m];
4857 return true;
4858}
4859
4860bool CiA402MotionControl::setGearboxRatio(int m, const double val)
4861{
4862 // The setGearboxRatio function is not implemented
4863 yCError(CIA402, "%s: The setGearboxRatio function is not implemented", Impl::kClassName.data());
4864 return false;
4865}
4866
4867bool CiA402MotionControl::getCurrent(int m, double* curr)
4868{
4869 if (curr == nullptr)
4870 {
4871 yCError(CIA402, "%s: getCurrent: null pointer", Impl::kClassName.data());
4872 return false;
4873 }
4874 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
4875 {
4876 yCError(CIA402, "%s: getCurrent: motor %d out of range", Impl::kClassName.data(), m);
4877 return false;
4878 }
4879 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4880 *curr = m_impl->variables.motorCurrents[m];
4881 return true;
4882};
4883
4885{
4886 if (currs == nullptr)
4887 {
4888 yCError(CIA402, "%s: getCurrents: null pointer", Impl::kClassName.data());
4889 return false;
4890 }
4891 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4892 std::memcpy(currs, m_impl->variables.motorCurrents.data(), m_impl->numAxes * sizeof(double));
4893 return true;
4894}
4895
4896bool CiA402MotionControl::getCurrentRange(int m, double* min, double* max)
4897{
4898 if (min == nullptr || max == nullptr)
4899 {
4900 yCError(CIA402, "%s: getCurrentRange: null pointer", Impl::kClassName.data());
4901 return false;
4902 }
4903 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
4904 {
4905 yCError(CIA402, "%s: getCurrentRange: motor %d out of range", Impl::kClassName.data(), m);
4906 return false;
4907 }
4908 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4909 *min = -m_impl->maxCurrentsA[m];
4910 *max = m_impl->maxCurrentsA[m];
4911 return true;
4912}
4913
4914bool CiA402MotionControl::getCurrentRanges(double* min, double* max)
4915{
4916 if (min == nullptr || max == nullptr)
4917 {
4918 yCError(CIA402, "%s: getCurrentRanges: null pointer", Impl::kClassName.data());
4919 return false;
4920 }
4921 std::lock_guard<std::mutex> lock(m_impl->variables.mutex);
4922 for (size_t m = 0; m < m_impl->numAxes; ++m)
4923 {
4924 min[m] = -m_impl->maxCurrentsA[m];
4925 max[m] = m_impl->maxCurrentsA[m];
4926 }
4927 return true;
4928}
4929
4931{
4932 if (currs == nullptr)
4933 {
4934 yCError(CIA402, "%s: setRefCurrents: null pointer", Impl::kClassName.data());
4935 return false;
4936 }
4937
4938 {
4939 // check that all the joints are in CURRENT mode
4940 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
4941 for (size_t j = 0; j < m_impl->numAxes; ++j)
4942 {
4943 if (m_impl->controlModeState.active[j] != VOCAB_CM_CURRENT)
4944 {
4945 yCError(CIA402,
4946 "%s: setRefCurrents rejected: CURRENT mode is not active for the joint "
4947 "%zu",
4948 Impl::kClassName.data(),
4949 j);
4950 return false; // reject
4951 }
4952 }
4953 }
4954
4955 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4956 std::memcpy(m_impl->setPoints.motorCurrents.data(), currs, m_impl->numAxes * sizeof(double));
4957 std::fill(m_impl->setPoints.hasCurrentSP.begin(), m_impl->setPoints.hasCurrentSP.end(), true);
4958 return true;
4959}
4960
4962{
4963 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
4964 {
4965 yCError(CIA402, "%s: setRefCurrent: motor %d out of range", Impl::kClassName.data(), m);
4966 return false;
4967 }
4968
4969 // (a/b) Only accept if CURRENT is ACTIVE; otherwise reject (not considered)
4970 {
4971 std::lock_guard<std::mutex> g(m_impl->controlModeState.mutex);
4972 if (m_impl->controlModeState.active[m] != VOCAB_CM_CURRENT)
4973 {
4974 yCError(CIA402,
4975 "%s: setRefCurrent rejected: CURRENT mode is not active for the joint %d",
4976 Impl::kClassName.data(),
4977 m);
4978 return false;
4979 }
4980 }
4981
4982 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
4983 m_impl->setPoints.motorCurrents[m] = curr;
4984 m_impl->setPoints.hasCurrentSP[m] = true; // (b)
4985
4986 return true;
4987}
4988
4989bool CiA402MotionControl::setRefCurrents(const int n_motor, const int* motors, const double* currs)
4990{
4991 if (currs == nullptr || motors == nullptr)
4992 {
4993 yCError(CIA402, "%s: setRefCurrents: null pointer", Impl::kClassName.data());
4994 return false;
4995 }
4996 if (n_motor <= 0)
4997 {
4998 yCError(CIA402,
4999 "%s: setRefCurrents: invalid number of motors %d",
5000 Impl::kClassName.data(),
5001 n_motor);
5002 return false;
5003 }
5004 for (int k = 0; k < n_motor; ++k)
5005 {
5006 if (motors[k] < 0 || motors[k] >= static_cast<int>(m_impl->numAxes))
5007 {
5008 yCError(CIA402,
5009 "%s: setRefCurrents: motor %d out of range",
5010 Impl::kClassName.data(),
5011 motors[k]);
5012 return false;
5013 }
5014 }
5015
5016 // check that all the joints are in CURRENT mode
5017 {
5018 std::lock_guard<std::mutex> lock(m_impl->controlModeState.mutex);
5019 for (int k = 0; k < n_motor; ++k)
5020 {
5021 if (m_impl->controlModeState.active[motors[k]] != VOCAB_CM_CURRENT)
5022 {
5023 yCError(CIA402,
5024 "%s: setRefCurrents rejected: CURRENT mode is not active for the joint %d",
5025 Impl::kClassName.data(),
5026 motors[k]);
5027 return false; // reject
5028 }
5029 }
5030 }
5031
5032 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
5033 for (int k = 0; k < n_motor; ++k)
5034 {
5035 m_impl->setPoints.motorCurrents[motors[k]] = currs[k];
5036 m_impl->setPoints.hasCurrentSP[motors[k]] = true;
5037 }
5038 return true;
5039}
5040
5042{
5043 if (currs == nullptr)
5044 {
5045 yCError(CIA402, "%s: getRefCurrents: null pointer", Impl::kClassName.data());
5046 return false;
5047 }
5048
5049 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
5050 std::memcpy(currs, m_impl->setPoints.motorCurrents.data(), m_impl->numAxes * sizeof(double));
5051 return true;
5052}
5053
5054bool CiA402MotionControl::getRefCurrent(int m, double* curr)
5055{
5056 if (curr == nullptr)
5057 {
5058 yCError(CIA402, "%s: getRefCurrent: null pointer", Impl::kClassName.data());
5059 return false;
5060 }
5061 if (m < 0 || m >= static_cast<int>(m_impl->numAxes))
5062 {
5063 yCError(CIA402, "%s: getRefCurrent: motor %d out of range", Impl::kClassName.data(), m);
5064 return false;
5065 }
5066
5067 std::lock_guard<std::mutex> lock(m_impl->setPoints.mutex);
5068 *curr = m_impl->setPoints.motorCurrents[m];
5069 return true;
5070}
5071
5072bool CiA402MotionControl::setLimits(int axis, double min, double max)
5073{
5074 if (axis < 0 || axis >= static_cast<int>(m_impl->numAxes))
5075 {
5076 yCError(CIA402, "%s: setLimits: axis %d out of range", Impl::kClassName.data(), axis);
5077 return false;
5078 }
5079 // If both bounds are provided (non-negative), enforce min < max.
5080 // When either bound is negative, we treat that side as disabled like in open(),
5081 // and skip the ordering check.
5082 if (!(min < 0.0 || max < 0.0) && (min >= max))
5083 {
5084 yCError(CIA402,
5085 "%s: setLimits: invalid limits [min=%g, max=%g]",
5086 Impl::kClassName.data(),
5087 min,
5088 max);
5089 return false;
5090 }
5091
5092 {
5093 std::lock_guard<std::mutex> lock(m_impl->limits.mutex);
5094 m_impl->limits.maxPositionLimitDeg[axis] = max;
5095 m_impl->limits.minPositionLimitDeg[axis] = min;
5096 }
5097
5098 // set the software limits in the drive (SDO 0x607D)
5099 // convert the limits from deg to counts, honoring inversion and disabled bounds
5100 const bool inv = m_impl->invertedMotionSenseDirection[axis];
5101 const bool lowerLimitDisabled = (min < 0.0);
5102 const bool upperLimitDisabled = (max < 0.0);
5103
5104 const auto lowerLimitCounts
5105 = lowerLimitDisabled ? 0 : m_impl->jointDegToTargetCounts(size_t(axis), min);
5106 const auto upperLimitCounts
5107 = upperLimitDisabled ? 0 : m_impl->jointDegToTargetCounts(size_t(axis), max);
5108
5109 int32_t minCounts = 0;
5110 int32_t maxCounts = 0;
5111
5112 if (!inv)
5113 {
5114 minCounts = lowerLimitDisabled ? std::numeric_limits<int32_t>::min() : lowerLimitCounts;
5115 maxCounts = upperLimitDisabled ? std::numeric_limits<int32_t>::max() : upperLimitCounts;
5116 } else
5117 {
5118 // Inverted: f(x) = -counts(x), so [min,max] -> [f(max), f(min)]
5119 minCounts = upperLimitDisabled ? std::numeric_limits<int32_t>::min() : -upperLimitCounts;
5120 maxCounts = lowerLimitDisabled ? std::numeric_limits<int32_t>::max() : -lowerLimitCounts;
5121 }
5122
5123 return m_impl->setPositionCountsLimits(axis, minCounts, maxCounts);
5124}
5125
5126bool CiA402MotionControl::getLimits(int axis, double* min, double* max)
5127{
5128 if (min == nullptr || max == nullptr)
5129 {
5130 yCError(CIA402, "%s: getLimits: null pointer", Impl::kClassName.data());
5131 return false;
5132 }
5133 if (axis < 0 || axis >= static_cast<int>(m_impl->numAxes))
5134 {
5135 yCError(CIA402, "%s: getLimits: axis %d out of range", Impl::kClassName.data(), axis);
5136 return false;
5137 }
5138
5139 std::lock_guard<std::mutex> lock(m_impl->limits.mutex);
5140 *min = m_impl->limits.minPositionLimitDeg[axis];
5141 *max = m_impl->limits.maxPositionLimitDeg[axis];
5142 return true;
5143}
5144
5145bool CiA402MotionControl::setVelLimits(int axis, double min, double max)
5146{
5147 // not implemented yet
5148 constexpr auto logPrefix = "[setVelLimits] ";
5149 yCError(CIA402, "%s: The setVelLimits function is not implemented", logPrefix);
5150 return false;
5151}
5152
5153bool CiA402MotionControl::getVelLimits(int axis, double* min, double* max)
5154{
5155 // not implemented yet
5156 constexpr auto logPrefix = "[getVelLimits] ";
5157 yCError(CIA402, "%s: The getVelLimits function is not implemented", logPrefix);
5158 return false;
5159}
5160
5161bool CiA402MotionControl::getInteractionMode(int axis, yarp::dev::InteractionModeEnum* mode)
5162{
5163 if (!mode)
5164 {
5165 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
5166 return false;
5167 }
5168
5169 *mode = m_impl->dummyInteractionMode;
5170 return true;
5171}
5172
5174 int* joints,
5175 yarp::dev::InteractionModeEnum* modes)
5176{
5177 if (!joints || !modes || n_joints <= 0)
5178 {
5179 yCError(CIA402, "%s: invalid args", Impl::kClassName.data());
5180 return false;
5181 }
5182
5183 for (int k = 0; k < n_joints; ++k)
5184 {
5185 if (joints[k] < 0 || joints[k] >= static_cast<int>(m_impl->numAxes))
5186 {
5187 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
5188 return false;
5189 }
5190 modes[k] = m_impl->dummyInteractionMode;
5191 }
5192 return true;
5193}
5194
5195bool CiA402MotionControl::getInteractionModes(yarp::dev::InteractionModeEnum* modes)
5196{
5197 if (modes == nullptr)
5198 {
5199 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
5200 return false;
5201 }
5202
5203 for (size_t j = 0; j < m_impl->numAxes; ++j)
5204 {
5205 modes[j] = m_impl->dummyInteractionMode;
5206 }
5207 return true;
5208}
5209
5210bool CiA402MotionControl::setInteractionMode(int axis, yarp::dev::InteractionModeEnum mode)
5211{
5212 if (axis < 0 || axis >= static_cast<int>(m_impl->numAxes))
5213 {
5214 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), axis);
5215 return false;
5216 }
5217
5218 // The interaction mode is not implemented in this driver.
5219 yCError(CIA402,
5220 "%s: The setInteractionMode function is not implemented",
5221 Impl::kClassName.data());
5222 return false;
5223}
5224
5226 int* joints,
5227 yarp::dev::InteractionModeEnum* modes)
5228{
5229 if (!joints || !modes || n_joints <= 0)
5230 {
5231 yCError(CIA402, "%s: invalid args", Impl::kClassName.data());
5232 return false;
5233 }
5234
5235 for (int k = 0; k < n_joints; ++k)
5236 {
5237 if (joints[k] < 0 || joints[k] >= static_cast<int>(m_impl->numAxes))
5238 {
5239 yCError(CIA402, "%s: joint %d out of range", Impl::kClassName.data(), joints[k]);
5240 return false;
5241 }
5242 }
5243
5244 // The interaction mode is not implemented in this driver.
5245 yCError(CIA402,
5246 "%s: The setInteractionModes function is not implemented",
5247 Impl::kClassName.data());
5248 return false;
5249}
5250
5251bool CiA402MotionControl::setInteractionModes(yarp::dev::InteractionModeEnum* modes)
5252{
5253 if (modes == nullptr)
5254 {
5255 yCError(CIA402, "%s: null pointer", Impl::kClassName.data());
5256 return false;
5257 }
5258
5259 yCError(CIA402,
5260 "%s: The setInteractionModes function is not implemented",
5261 Impl::kClassName.data());
5262 return false;
5263}
5264
5265} // namespace yarp::dev
T append(T... args)
T begin(T... args)
T c_str(T... args)
Minimal EtherCAT master built on SOEM for CiA-402 devices.
TxView getTxView(int slaveIndex) const noexcept
Obtain a typed, bounds-checked view over the TxPDO (slave→master).
const RxPDO * getRxPDO(int slaveIndex) const noexcept
Access the RxPDO (master→slave) buffer for a given slave.
@ NoError
Operation completed successfully.
Error writeSDO(int slaveIndex, uint16_t idx, uint8_t subIdx, const T &value) noexcept
Write an SDO value to a slave (blocking call).
static bool isOperationEnabled(uint16_t sw)
static bool isFault(uint16_t sw)
static bool isFaultReactionActive(uint16_t sw)
T get(TxField f, T fallback={}) const
Read a field from the TxPDO image with a typed accessor.
bool setGearboxRatio(int m, const double val) override
Sets the gearbox ratio of a specific motor.
bool setRefAcceleration(int j, double acc) override
(Unused in CSV mode) Sets the reference acceleration for a specific joint.
bool getTargetPosition(int j, double *ref) override
Gets the target position for a specific joint.
bool getCurrentRange(int m, double *min, double *max) override
Gets the allowable current range for a specific motor.
bool resetMotorEncoders() override
Resets all motor encoders to zero.
bool setRefCurrent(int m, double curr) override
Sets the reference current for a specific motor.
bool setEncoder(int j, double val) override
Sets the value of a specific encoder.
bool getVelLimits(int axis, double *min, double *max) override
Gets the velocity limits for a specific axis.
void run() override
Runs the periodic thread.
bool setMotorEncoder(int m, const double val) override
Sets the value of a specific motor encoder.
bool getRefVelocity(const int joint, double *vel) override
Gets the reference velocity for a specific joint.
bool setMotorEncoders(const double *vals) override
Sets the values of all motor encoders.
bool getNumberOfMotors(int *num) override
Gets the number of motors controlled by the device.
bool getEncoderAcceleration(int j, double *spds) override
Gets the acceleration of a specific encoder.
bool getEncoderSpeed(int j, double *sp) override
Gets the speed of a specific encoder.
bool getEncoders(double *encs) override
Gets the values of all encoders.
bool getEncoderSpeeds(double *spds) override
Gets the speeds of all encoders.
bool setVelLimits(int axis, double min, double max) override
Sets the velocity limits for a specific axis.
bool positionMove(int j, double ref) override
Commands an absolute position move for a specific joint using Profile Position Mode (PP).
bool getMotorEncoder(int m, double *v) override
Gets the value of a specific motor encoder.
bool getEncoderTimed(int j, double *encs, double *time) override
Gets the value and timestamp of a specific encoder.
bool getAxisName(int axis, std::string &name) override
Gets the name of a specific axis.
bool setPosition(int j, double ref) override
Streams a single joint reference in Cyclic Synchronous Position mode.
bool relativeMove(int j, double delta) override
Commands a relative position move for a specific joint.
bool getLastJointFault(int j, int &fault, std::string &message) override
Gets the last joint fault for a specific joint.
bool getJointType(int axis, yarp::dev::JointTypeEnum &type) override
Gets the type of a specific axis.
bool getRefPosition(const int joint, double *ref) override
Returns the most recent position-direct command for a joint.
bool getMotorEncoderCountsPerRevolution(int m, double *cpr) override
Gets the counts per revolution for a specific motor encoder.
~CiA402MotionControl() override
Destructor.
bool resetEncoders() override
Resets all encoders to zero.
bool getTargetPositions(double *refs) override
Gets the target positions for all joints.
bool setRefCurrents(const double *currs) override
Sets the reference currents for all motors.
bool getTorques(double *t) override
Gets the measured torques for all joints.
bool getRefCurrent(int m, double *curr) override
Gets the last commanded reference current for a specific motor.
bool getRefCurrents(double *currs) override
Gets the last commanded reference currents for all motors.
bool stop() override
Stops motion for all joints.
bool setRefTorques(const double *t) override
Sets the reference torques for all joints.
bool getControlMode(int j, int *mode) override
Gets the control mode of a specific joint.
bool getEncoderAccelerations(double *accs) override
Gets the accelerations of all encoders.
bool getRefSpeed(int j, double *ref) override
Gets the current reference speed (profile velocity) for a specific joint.
bool setLimits(int axis, double min, double max) override
Sets the position limits for a specific axis.
bool setInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Sets the interaction modes of a subset of joints.
bool setTemperatureLimit(int m, const double temp) override
Sets the temperature limit of a specific motor.
bool getTorque(int j, double *t) override
Gets the measured torque for a specific joint.
bool getRefPositions(double *refs) override
Returns the position-direct references for all joints.
bool getLimits(int axis, double *min, double *max) override
Gets the position limits for a specific axis.
bool velocityMove(int j, double sp) override
Commands a velocity move for a specific joint.
bool setMotorEncoderCountsPerRevolution(int m, const double cpr) override
Sets the counts per revolution for a specific motor encoder.
bool getRefVelocities(double *vels) override
Gets the reference velocities for all joints.
bool getEncodersTimed(double *encs, double *time) override
Gets the values and timestamps of all encoders.
bool getTorqueRanges(double *min, double *max) override
Gets the torque ranges for all joints.
bool getControlModes(int *modes) override
Gets the control modes of all joints.
bool resetEncoder(int j) override
Resets the specified encoder to zero.
bool setControlModes(const int n, const int *joints, int *modes) override
Sets the control modes of a subset of joints.
bool getMotorEncoderSpeed(int m, double *sp) override
Gets the speed of a specific motor encoder.
bool getMotorEncoders(double *encs) override
Gets the values of all motor encoders.
bool setPositions(const int n_joint, const int *joints, const double *refs) override
Streams references for a subset of joints.
bool setRefSpeed(int j, double sp) override
Sets the reference speed (profile velocity) for a specific joint.
bool getMotorEncoderAcceleration(int m, double *acc) override
Gets the acceleration of a specific motor encoder.
bool getEncoder(int j, double *v) override
Gets the value of a specific encoder.
bool getMotorEncoderTimed(int m, double *encs, double *time) override
Gets the value and timestamp of a specific motor encoder.
bool getCurrentRanges(double *min, double *max) override
Gets the allowable current ranges for all motors.
bool setControlMode(const int j, const int mode) override
Sets the control mode of a specific joint.
bool getTemperatureLimit(int m, double *temp) override
Gets the temperature limit of a specific motor.
bool getInteractionMode(int axis, yarp::dev::InteractionModeEnum *mode) override
Gets the interaction mode of a specific axis.
bool getRefAcceleration(int j, double *acc) override
(Unused in CSV mode) Gets the reference acceleration for a specific joint.
bool getCurrents(double *currs) override
Gets the measured currents of all motors.
bool checkMotionDone(int j, bool *flag) override
Checks if a specific joint has completed its motion.
bool getGearboxRatio(int m, double *val) override
Gets the gearbox ratio of a specific motor.
bool open(yarp::os::Searchable &config) override
Opens the device driver.
bool getTemperature(int m, double *val) override
Gets the temperature of a specific motor.
bool setRefSpeeds(const double *spds) override
Sets the reference speeds (profile velocities) for all joints.
bool getInteractionModes(int n_joints, int *joints, yarp::dev::InteractionModeEnum *modes) override
Gets the interaction modes of a subset of joints.
bool setRefAccelerations(const double *accs) override
(Unused in CSV mode) Sets the reference accelerations for all joints.
bool getMotorEncodersTimed(double *encs, double *time) override
Gets the values and timestamps of all motor encoders.
bool getMotorEncoderAccelerations(double *accs) override
Gets the accelerations of all motor encoders.
bool getRefTorque(int j, double *t) override
Gets the reference torque for a specific joint.
bool setEncoders(const double *vals) override
Sets the values of all encoders.
bool close() override
Closes the device driver.
bool getNumberOfMotorEncoders(int *num) override
Gets the number of motor encoders.
bool getCurrent(int m, double *curr) override
Gets the measured current of a specific motor.
bool getAxes(int *ax) override
Gets the number of axes (encoders).
bool setRefTorque(int j, double t) override
Sets the reference torque for a specific joint.
bool getTemperatures(double *vals) override
Gets the temperatures of all motors.
bool getMotorEncoderSpeeds(double *spds) override
Gets the speeds of all motor encoders.
bool resetMotorEncoder(int m) override
Resets the specified motor encoder to zero.
bool getRefTorques(double *t) override
Gets the reference torques for all joints.
bool setInteractionMode(int axis, yarp::dev::InteractionModeEnum mode) override
Sets the interaction mode of a specific axis.
bool getTorqueRange(int j, double *min, double *max) override
Gets the torque range for a specific joint.
bool getRefAccelerations(double *accs) override
(Unused in CSV mode) Gets the reference accelerations for all joints.
bool getRefSpeeds(double *spds) override
Gets the current reference speeds (profile velocities) for all joints.
T duration_cast(T... args)
T fill(T... args)
T find(T... args)
T snprintf(T... args)
T isinf(T... args)
T max(T... args)
T memcpy(T... args)
T memset(T... args)
T min(T... args)
@ Velocity606C
0x606C: Velocity actual value
@ Enc2Pos2113_02
0x2113:02 Vendor enc2 position
@ SBC_6621_02
0x6621:02 Safe Brake Control status (exposed via PDO)
@ Enc2Vel2113_03
0x2113:03 Vendor enc2 velocity
@ OpModeDisplay
0x6061: Modes of operation display
@ Timestamp20F0
0x20F0: Timestamp (if supported)
@ Statusword
0x6041: Statusword
@ TemperatureDrive
0x2031:01 Temperature (if supported)
@ Position6064
0x6064: Position actual value
@ Torque6077
0x6077: Torque actual value
@ Enc1Pos2111_02
0x2111:02 Vendor enc1 position
@ Enc1Vel2111_03
0x2111:03 Vendor enc1 velocity
@ STO_6621_01
0x6621:01 Safe Torque Off status (exposed via PDO)
STL namespace.
T push_back(T... args)
T resize(T... args)
T round(T... args)
T size(T... args)
Process Data Object written from master to slave (RxPDO).
int8_t OpMode
0x6060: Modes of operation
uint16_t Controlword
0x6040: Controlword
static constexpr std::string_view kClassName
bool setPositionControlStrategy(uint16_t strategyValue)
static std::string_view yarpToString(int op)
yarp::dev::InteractionModeEnum dummyInteractionMode
bool setPositionWindowDeg(int j, double winDeg, double winTime_ms)
static constexpr uint64_t TIMESTAMP_WRAP_PERIOD_US
static std::tuple< double, double, const char * > decode60A9(uint32_t v)
static constexpr uint32_t TIMESTAMP_WRAP_HALF_RANGE
int32_t jointDegToTargetCounts(size_t j, double jointDeg) const
std::chrono::steady_clock::time_point avgWindowStart
double loopCountsToJointDeg(std::size_t j, double counts) const
std::vector< std::unique_ptr< CiA402::StateMachine > > sm
bool readSimplePidGains(std::vector< double > &kpNmPerDeg, std::vector< double > &kdNmSecPerDeg)
struct yarp::dev::CiA402MotionControl::Impl::Limits limits
bool configureSimplePidGains(const std::vector< double > &kpNmPerDeg, const std::vector< double > &kdNmSecPerDeg)
bool setPositionCountsLimits(int axis, int32_t minCounts, int32_t maxCounts)
static constexpr double MICROSECONDS_TO_SECONDS
bool getPositionControlStrategy(uint16_t &strategyValue)
int ciaOpToYarpWithFlavor(int op, int cstFlavor)
double targetCountsToJointDeg(size_t j, int32_t counts) const