11#include <yarp/os/LogStream.h>
12#include <yarp/os/Value.h>
70 static constexpr std::string_view
kClassName =
"CiA402MotionControl";
174 target.assign(n, VOCAB_CM_IDLE);
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);
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);
236 std::fill(this->ppPulseCoolDown.
begin(), this->ppPulseCoolDown.end(),
false);
239 this->positionDirectJointTargetsDeg.end(),
242 this->positionDirectTargetCounts.end(),
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;
299 yarp::dev::InteractionModeEnum::VOCAB_IM_STIFF};
333 double shaftDeg = jointDeg;
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);
354 const int32_t cAdj = inv ? -counts : counts;
383 const double shaftDeg = res ? (double(cAdj) / double(res)) * 360.0 : 0.0;
395 constexpr auto logPrefix =
"[setPositionCountsLimits]";
403 "%s: setLimits: SDO write 0x607D:01 (min) failed for axis %d",
416 "%s: setLimits: SDO write 0x607D:02 (max) failed for axis %d",
430 constexpr auto logPrefix =
"[readEncoderResolutions]";
437 for (
size_t j = 0; j <
numAxes; ++j)
449 for (
size_t j = 0; j <
numAxes; ++j)
456 yCInfo(CIA402,
"%s successfully read encoder resolutions from SDO", logPrefix);
457 for (
size_t j = 0; j <
numAxes; ++j)
460 "%s j=%zu enc1_resolution=%u (inv=%.9f), enc2_resolution=%u (inv=%.9f)",
476 if (v == 0x00B44700u)
477 return {6.0, 1.0 / 6.0,
"1 RPM"};
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"};
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"};
495 return {6.0, 1.0 / 6.0,
"UNKNOWN (assume 1 RPM)"};
500 constexpr auto logPrefix =
"[readSiVelocityUnits]";
505 for (
size_t j = 0; j <
numAxes; ++j)
510 uint32_t raw = 0x00B44700u;
513 auto [toDegS, toDev, name] = this->
decode60A9(raw);
519 "%s j=%zu 0x60A9=0x%08X velocity_unit=%s (1_unit=%.6f_deg/s)",
526 yWarning(
"%s j=%zu failed to read 0x60A9, assuming 1_RPM (1_unit=6_deg/s)",
531 yCInfo(CIA402,
"%s successfully read velocity conversion units from SDO", logPrefix);
566 const double shaftDeg = (counts / double(res)) * 360.0;
570 "loopCountsToJointDeg j=%zu counts=%.3f res=%u mount=%d -> shaftDeg=%.9f",
574 static_cast<int>(mount),
584 if (j < 0 || j >=
static_cast<int>(this->
numAxes))
587 "%s: setPositionWindowDeg: invalid joint index",
597 rawWin = 0xFFFFFFFFu;
600 rawWin =
static_cast<uint32_t
>(
605 auto e1 = this->ethercatManager.
writeSDO<uint32_t>(s, 0x6067, 0x00, rawWin);
609 "%s: setPositionWindowDeg: SDO 0x6067 write failed on joint %d",
614 auto e2 = this->ethercatManager.
writeSDO<uint32_t>(s, 0x6068, 0x00, rawTime);
618 "%s: setPositionWindowDeg: SDO 0x6068 write failed on joint %d",
628 constexpr auto logPrefix =
"[getPositionControlStrategy]";
633 =
ethercatManager.readSDO<uint16_t>(slaveIdx, 0x2002, 0x00, strategyValue);
637 "%s failed to read 0x2002:00",
643 "%s read position strategy %u from first axis",
645 static_cast<unsigned>(strategyValue));
651 constexpr auto logPrefix =
"[setPositionControlStrategy]";
653 for (
size_t j = 0; j <
numAxes; ++j)
655 const int slaveIdx =
firstSlave +
static_cast<int>(j);
657 =
ethercatManager.writeSDO<uint16_t>(slaveIdx, 0x2002, 0x00, strategyValue);
661 "%s j=%zu failed to set 0x2002:00 (value=%u)",
664 static_cast<unsigned>(strategyValue));
670 "%s configured %zu axes with position strategy %u",
673 static_cast<unsigned>(strategyValue));
681 constexpr auto logPrefix =
"[readSimplePidGains]";
686 for (
size_t j = 0; j <
numAxes; ++j)
688 const int slaveIdx =
firstSlave +
static_cast<int>(j);
689 float32 kpValue = 0.0f;
690 float32 kdValue = 0.0f;
692 const auto errKp =
ethercatManager.readSDO<float32>(slaveIdx, 0x2012, 0x01, kpValue);
693 const auto errKd =
ethercatManager.readSDO<float32>(slaveIdx, 0x2012, 0x03, kdValue);
699 "%s j=%zu failed to read gains (errs=%d,%d)",
702 static_cast<int>(errKp),
703 static_cast<int>(errKd));
708 const double kpMotor_mNm_per_deg =
static_cast<double>(kpValue) / degPerCount;
709 const double kdMotor_mNmS_per_deg =
static_cast<double>(kdValue) / degPerCount;
711 kpNmPerDeg[j] = (kpMotor_mNm_per_deg *
gearRatio[j]) / 1000.0;
712 kdNmSecPerDeg[j] = (kdMotor_mNmS_per_deg *
gearRatio[j]) / 1000.0;
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]",
723 kdMotor_mNmS_per_deg,
727 yCInfo(CIA402,
"%s read simple PID gains for %zu axes", logPrefix,
numAxes);
734 constexpr auto logPrefix =
"[configureSimplePidGains]";
739 "%s mismatched gain vector sizes (kp=%zu kd=%zu expected=%zu)",
742 kdNmSecPerDeg.
size(),
747 for (
size_t j = 0; j <
numAxes; ++j)
751 yCError(CIA402,
"%s j=%zu invalid gear ratio (0)", logPrefix, j);
756 if (degPerCount == 0.0)
759 "%s j=%zu cannot derive counts/deg (loop source missing)",
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;
767 const double kpDevice = kpMotor_mNm_per_deg * degPerCount;
768 const double kdDevice = kdMotor_mNmS_per_deg * degPerCount;
770 const float32 kpValue =
static_cast<float32
>(kpDevice);
771 const float32 kdValue =
static_cast<float32
>(kdDevice);
772 constexpr float32 kiValue = 0.0f;
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]",
786 kdMotor_mNmS_per_deg,
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);
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]",
804 static_cast<int>(errKp),
805 static_cast<int>(errKi),
806 static_cast<int>(errKd),
815 "%s j=%zu Kp=%.3f[mNm/inc] Kd=%.3f[mNm*s/inc]",
822 yCInfo(CIA402,
"%s programmed simple PID gains for %zu axes", logPrefix,
numAxes);
828 constexpr auto logPrefix =
"[readMotorConstants]";
833 for (
size_t j = 0; j <
numAxes; ++j)
836 int32_t tcMicroNmA = 0;
841 yWarning(
"%s j=%zu cannot read torque constant (0x2003:02) or zero, assuming 1.0 "
854 uint32_t ratedCurrentMilliA = 0;
855 double ratedCurrentA = 0.0;
856 if (
ethercatManager.readSDO<uint32_t>(s, 0x6075, 0x00, ratedCurrentMilliA)
858 || ratedCurrentMilliA == 0)
860 yWarning(
"%s j=%zu cannot read motor rated current (0x6075:00) or zero, assuming "
868 ratedCurrentA = double(ratedCurrentMilliA) * 1e-3;
872 uint16_t maxPermille = 0;
876 yWarning(
"%s j=%zu cannot read max current (0x6073:00), assuming 1000 per_mille",
883 "%s j=%zu max_current=%u_permille (%.3fA), torque_constant=%.6f_Nm/A",
887 (
double(maxPermille) / 1000.0) * ratedCurrentA,
888 this->torqueConstants[j]);
890 maxCurrentsA[j] = (double(maxPermille) / 1000.0) * ratedCurrentA;
893 yCInfo(CIA402,
"%s successfully read motor constants from SDO", logPrefix);
908 constexpr auto logPrefix =
"[readGearRatios]";
913 for (
size_t j = 0; j <
numAxes; ++j)
915 const int slaveIdx =
firstSlave +
static_cast<int>(j);
924 yWarning(
"%s j=%zu gear_ratio_numerator not available (0x6091:01), assuming 1",
935 yWarning(
"%s j=%zu gear_ratio_denominator not available/zero (0x6091:02), assuming "
943 "%s j=%zu gear_ratio=%u:%u (ratio=%.6f)",
948 static_cast<double>(num) /
static_cast<double>(den));
951 gearRatio[j] =
static_cast<double>(num) /
static_cast<double>(den);
955 for (
size_t j = 0; j <
numAxes; ++j)
960 yCInfo(CIA402,
"%s successfully read gear ratios from SDO", logPrefix);
966 constexpr auto logPrefix =
"[readTorqueValues]";
971 for (
size_t j = 0; j <
numAxes; ++j)
974 uint32_t rated_mNm = 0;
978 yCError(CIA402,
"%s j=%zu cannot read rated torque (0x6076:00)", logPrefix, j);
983 for (
size_t j = 0; j <
numAxes; ++j)
986 uint16_t maxPerm = 0;
990 yCError(CIA402,
"%s j=%zu cannot read max torque (0x6072:00)", logPrefix, j);
995 "%s j=%zu motor_rated_torque=%.3fNm max_torque=%.3fNm",
1002 yCInfo(CIA402,
"%s successfully read torque values from SDO", logPrefix);
1009 double shaft_deg_s = spDegS;
1010 switch (this->posLoopSrc[j])
1014 shaft_deg_s = spDegS * this->gearRatio[j];
1016 shaft_deg_s = spDegS;
1020 shaft_deg_s = spDegS * this->gearRatio[j];
1022 shaft_deg_s = spDegS;
1030 shaft_deg_s = spDegS * this->gearRatio[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);
1050 for (
size_t j = 0; j < this->
numAxes; ++j)
1053 auto rx = this->ethercatManager.
getRxPDO(s);
1054 const int opMode = this->controlModeState.
active[j];
1057 rx->TargetPosition = 0;
1058 rx->TargetTorque = 0;
1059 rx->TargetVelocity = 0;
1062 if (opMode == VOCAB_CM_TORQUE)
1064 if (!this->trqLatched[j])
1066 rx->TargetTorque = 0;
1067 this->trqLatched[j] =
true;
1076 const int16_t tq_thousand =
static_cast<int16_t
>(
std::llround(
1079 rx->TargetTorque = this->invertedMotionSenseDirection[j] ? -tq_thousand
1085 if (opMode == VOCAB_CM_VELOCITY)
1089 rx->TargetVelocity = 0;
1100 double shaft_deg_s = joint_deg_s;
1108 shaft_deg_s = joint_deg_s *
gearRatio[j];
1110 shaft_deg_s = joint_deg_s;
1116 shaft_deg_s = joint_deg_s *
gearRatio[j];
1118 shaft_deg_s = joint_deg_s;
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);
1137 if (opMode == VOCAB_CM_POSITION)
1141 rx->Controlword |= (1u << 8);
1143 rx->Controlword &= ~(1u << 8);
1148 rx->Controlword |= (1u << 5);
1149 rx->Controlword &= ~(1u << 4);
1153 const double currentJointDeg = this->variables.
jointPositions[j];
1154 const int32_t seedStoreCounts
1162 setPoints.ppTargetCounts[j] = seedStoreCounts;
1163 setPoints.ppJointTargetsDeg[j] = currentJointDeg;
1169 const int32_t driveTargetCounts = this->invertedMotionSenseDirection[j]
1172 rx->TargetPosition = driveTargetCounts;
1183 rx->Controlword |= (1u << 5);
1188 rx->Controlword &= ~(1u << 4);
1193 int32_t targetPositionCounts = 0;
1198 rx->Controlword |= (1u << 6);
1200 rx->Controlword &= ~(1u << 6);
1203 targetPositionCounts = this->invertedMotionSenseDirection[j]
1208 rx->Controlword |= (1u << 4);
1216 auto tx = this->ethercatManager.
getTxView(s);
1217 targetPositionCounts = this->invertedMotionSenseDirection[j]
1223 targetPositionCounts);
1226 setPoints.ppTargetCounts[j] = this->invertedMotionSenseDirection[j]
1227 ? -targetPositionCounts
1228 : targetPositionCounts;
1234 rx->TargetPosition = targetPositionCounts;
1239 if (opMode == VOCAB_CM_POSITION_DIRECT)
1243 const double currentJointDeg = this->variables.
jointPositions[j];
1245 setPoints.positionDirectJointTargetsDeg[j] = currentJointDeg;
1246 setPoints.positionDirectTargetCounts[j] = seedCounts;
1250 const int32_t driveCounts = this->invertedMotionSenseDirection[j]
1251 ? -
setPoints.positionDirectTargetCounts[j]
1252 :
setPoints.positionDirectTargetCounts[j];
1253 rx->TargetPosition = driveCounts;
1256 if (opMode == VOCAB_CM_CURRENT)
1258 if (!this->currLatched[j])
1261 rx->TargetTorque = 0;
1262 this->currLatched[j] =
true;
1270 const double torqueNm = currentA * this->torqueConstants[j];
1273 const int16_t tq_thousand =
static_cast<int16_t
>(
std::llround(
1276 rx->TargetTorque = this->invertedMotionSenseDirection[j] ? -tq_thousand
1295 auto shaftFromMount_pos = [&](
double deg,
Mount m,
size_t j,
bool asMotor) ->
double {
1302 return asMotor ? deg
1315 auto shaftFromMount_vel = [&](
double degs,
Mount m,
size_t j,
bool asMotor) ->
double {
1322 return asMotor ? degs *
gearRatio[j] : degs;
1327 for (
size_t j = 0; j < this->
numAxes; ++j)
1330 auto tx = this->ethercatManager.
getTxView(s);
1409 const double k = this->velToDegS[j];
1433 return {double(v606C) * k,
enc1Mount[j]};
1435 return {double(v606C) * k,
enc2Mount[j]};
1441 return {double(v606C) * k,
enc2Mount[j]};
1444 return {double(v606C) * k,
enc1Mount[j]};
1446 return {double(v606C) * k,
enc2Mount[j]};
1458 auto [degJ_src, mountJ] = posDegOnOwnShaft(
posSrcJoint[j]);
1459 auto [degM_src, mountM] = posDegOnOwnShaft(
posSrcMotor[j]);
1462 const double jointDeg = shaftFromMount_pos(degJ_src, mountJ, j,
false);
1463 const double motorDeg = shaftFromMount_pos(degM_src, mountM, j,
true);
1467 = this->invertedMotionSenseDirection[j] ? -jointDeg : jointDeg;
1469 = this->invertedMotionSenseDirection[j] ? -motorDeg : motorDeg;
1478 auto [degsJ_src, mountJ] = velDegSOnOwnShaft(
velSrcJoint[j]);
1480 auto [degsM_src, mountM] = velDegSOnOwnShaft(
velSrcMotor[j]);
1484 const double jointDegS
1485 = shaftFromMount_vel(degsJ_src, mountJ, j,
false);
1486 const double motorDegS = shaftFromMount_vel(degsM_src, mountM, j,
true);
1490 = this->invertedMotionSenseDirection[j] ? -jointDegS : jointDegS;
1492 = this->invertedMotionSenseDirection[j] ? -motorDegS : motorDegS;
1505 const double tq_per_thousand
1507 const double motorNm = tq_per_thousand * this->ratedMotorTorqueNm[j];
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];
1532 const uint32_t back = this->tsLastRaw[j] - raw;
1535 this->tsWraps[j] += 1u;
1539 this->tsLastRaw[j] = raw;
1541 const uint64_t us_ext
1569 case VOCAB_CM_FORCE_IDLE:
1571 case VOCAB_CM_POSITION:
1573 case VOCAB_CM_VELOCITY:
1575 case VOCAB_CM_TORQUE:
1576 case VOCAB_CM_CURRENT:
1578 case VOCAB_CM_POSITION_DIRECT:
1592 return (cstFlavor == VOCAB_CM_CURRENT) ? VOCAB_CM_CURRENT : VOCAB_CM_TORQUE;
1603 return VOCAB_CM_IDLE;
1605 return VOCAB_CM_POSITION;
1607 return VOCAB_CM_VELOCITY;
1609 return VOCAB_CM_POSITION_DIRECT;
1611 return VOCAB_CM_VELOCITY;
1613 return VOCAB_CM_TORQUE;
1615 return VOCAB_CM_UNKNOWN;
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";
1656 return "Continuous over current (device internal)";
1658 return "Short circuit (device internal)";
1660 return "Load level fault (I2t, thermal state)";
1662 return "Load level warning (I2t, thermal state)";
1664 return "Phase failure";
1666 return "Phase failure L1";
1668 return "Phase failure L2";
1670 return "Phase failure L3";
1672 return "DC link over-voltage";
1674 return "DC link under-voltage";
1676 return "Field circuit interrupted";
1678 return "Excess temperature device";
1680 return "Excess temperature drive";
1684 return "Operating unit";
1686 return "Software reset (watchdog)";
1688 return "Parameter error";
1690 return "Motor blocked";
1694 return "Resolver 1 fault";
1696 return "Resolver 2 fault";
1698 return "Communication";
1700 return "Positioning controller (reference limit)";
1702 return "Sub-synchronous run";
1706 switch (code & 0xFF00)
1709 return "Current/device-internal fault";
1711 return "Motor/output circuit fault";
1713 return "Phase/mains supply issue";
1715 return "DC link voltage issue";
1717 return "Field/armature circuit issue";
1719 return "Excess temperature (device)";
1721 return "Excess temperature (drive)";
1723 return "Control device hardware / limits";
1725 return "Operating unit / safety";
1727 return "Software reset / watchdog";
1729 return "Parameter/configuration error";
1731 return "Motor blocked / mechanical issue";
1733 return "Sensor/encoder fault";
1735 return "Communication/internal";
1737 return "Positioning controller (vendor specific)";
1739 return "Timing/performance warning";
1742 std::snprintf(buf,
sizeof(buf),
"Unknown 0x603F error: 0x%04X", code);
1754 :
yarp::os::PeriodicThread(period, useSysClock,
yarp::os::PeriodicThreadClock::Absolute)
1755 , m_impl(
std::make_unique<
Impl>())
1760 :
yarp::os::PeriodicThread(0.001 ,
1761 yarp::os::ShouldUseSystemClock::Yes,
1762 yarp::os::PeriodicThreadClock::Absolute)
1763 , m_impl(
std::make_unique<
Impl>())
1773 constexpr auto logPrefix =
"[open]";
1778 if (!cfg.check(
"ifname") || !cfg.find(
"ifname").isString())
1780 yCError(CIA402,
"%s: 'ifname' parameter is not a string",
Impl::kClassName.data());
1783 if (!cfg.check(
"num_axes") || !cfg.find(
"num_axes").isInt32())
1785 yCError(CIA402,
"%s: 'num_axes' parameter is not an integer",
Impl::kClassName.data());
1789 if (!cfg.check(
"period") || !cfg.find(
"period").isFloat64())
1791 yCError(CIA402,
"%s: 'period' parameter is not a float64",
Impl::kClassName.data());
1794 const double period = cfg.find(
"period").asFloat64();
1797 yCError(CIA402,
"%s: 'period' parameter must be positive",
Impl::kClassName.data());
1800 this->setPeriod(period);
1801 yCDebug(CIA402,
"%s: using period = %.6f s", logPrefix, period);
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();
1843 yWarning(
"%s: invalid mount '%s' (allowed: none|motor|joint) → 'none'",
1849 auto extractListOfStringFromSearchable = [
this](
const yarp::os::Searchable& cfg,
1855 if (!cfg.check(key))
1861 const yarp::os::Value& v = cfg.find(key);
1864 yCError(CIA402,
"%s: key '%s' is not a list",
Impl::kClassName.data(), key);
1868 const yarp::os::Bottle* lst = v.asList();
1872 "%s: internal error: list for key '%s' is null",
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)
1883 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
1891 result.reserve(expected);
1892 for (
int i = 0; i < lst->size(); ++i)
1894 const yarp::os::Value& elem = lst->get(i);
1896 if (!elem.isString())
1899 "%s: element %d in list for key '%s' is not a string",
1910 if (!acceptedKeys.empty())
1912 if (
std::find(acceptedKeys.begin(), acceptedKeys.end(), val) == acceptedKeys.end())
1915 "%s: invalid value '%s' in list for key '%s'",
1929 auto extractListOfDoubleFromSearchable = [
this](
const yarp::os::Searchable& cfg,
1934 if (!cfg.check(key))
1940 const yarp::os::Value& v = cfg.find(key);
1943 yCError(CIA402,
"%s: key '%s' is not a list",
Impl::kClassName.data(), key);
1947 const yarp::os::Bottle* lst = v.asList();
1951 "%s: internal error: list for key '%s' is null",
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)
1962 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
1970 result.reserve(expected);
1971 for (
int i = 0; i < lst->size(); ++i)
1973 const yarp::os::Value& elem = lst->get(i);
1975 if (!elem.isFloat64() && !elem.isInt32() && !elem.isInt64() && !elem.isFloat32())
1978 "%s: element %d in list for key '%s' is not a number",
1986 result.push_back(elem.asFloat64());
1992 auto extractListOfBoolFromSearchable = [
this](
const yarp::os::Searchable& cfg,
1997 if (!cfg.check(key))
2003 const yarp::os::Value& v = cfg.find(key);
2006 yCError(CIA402,
"%s: key '%s' is not a list",
Impl::kClassName.data(), key);
2010 const yarp::os::Bottle* lst = v.asList();
2014 "%s: internal error: list for key '%s' is null",
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)
2025 "%s: list for key '%s' has incorrect size (%zu), expected (%zu)",
2033 result.reserve(expected);
2034 for (
int i = 0; i < lst->size(); ++i)
2036 const yarp::os::Value& elem = lst->get(i);
2041 "%s: element %d in list for key '%s' is not a boolean",
2049 result.push_back(elem.asBool());
2061 if (!extractListOfStringFromSearchable(cfg,
"enc1_mount", {
"motor",
"joint"}, enc1MStr))
2063 if (!extractListOfStringFromSearchable(cfg,
"enc2_mount", {
"motor",
"joint",
"none"}, enc2MStr))
2070 if (!extractListOfStringFromSearchable(cfg,
2071 "position_feedback_joint",
2072 {
"6064",
"enc1",
"enc2"},
2075 if (!extractListOfStringFromSearchable(cfg,
2076 "position_feedback_motor",
2077 {
"6064",
"enc1",
"enc2"},
2080 if (!extractListOfStringFromSearchable(cfg,
2081 "velocity_feedback_joint",
2082 {
"606C",
"enc1",
"enc2"},
2085 if (!extractListOfStringFromSearchable(cfg,
2086 "velocity_feedback_motor",
2087 {
"606C",
"enc1",
"enc2"},
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;
2103 if (!extractListOfDoubleFromSearchable(cfg,
"position_window_deg", positionWindowDeg))
2105 if (!extractListOfDoubleFromSearchable(cfg,
"timing_window_ms", timingWindowMs))
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)
2114 "%s configuration must provide both simple_pid_kp_nm_per_deg and "
2115 "simple_pid_kd_nm_s_per_deg",
2119 if (programSimplePidGains)
2121 if (!extractListOfDoubleFromSearchable(cfg,
"simple_pid_kp_nm_per_deg", simplePidKpNmPerDeg))
2123 if (!extractListOfDoubleFromSearchable(cfg,
2124 "simple_pid_kd_nm_s_per_deg",
2125 simplePidKdNmSecPerDeg))
2129 for (
size_t j = 0; j < m_impl->numAxes; ++j)
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]));
2141 const int pdoTimeoutUs = cfg.check(
"pdo_timeout_us") ? cfg.find(
"pdo_timeout_us").asInt32()
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());
2147 if (!extractListOfBoolFromSearchable(cfg,
2148 "inverted_motion_sense_direction",
2149 m_impl->invertedMotionSenseDirection))
2154 for (
size_t i = 0; i < v.size(); ++i)
2156 s += (v[i] ?
"true" :
"false");
2157 if (i + 1 < v.size())
2164 "%s: inverted_motion_sense_direction = [%s]",
2166 vecBoolToString(m_impl->invertedMotionSenseDirection).c_str());
2172 const auto ecErr = m_impl->ethercatManager.init(ifname);
2176 "%s EtherCAT initialization failed with error code %d",
2178 static_cast<int>(ecErr));
2182 if (pdoTimeoutUs > 0)
2184 m_impl->ethercatManager.setPdoTimeoutUs(pdoTimeoutUs);
2186 "%s PDO receive timeout set to %d us",
2188 m_impl->ethercatManager.getPdoTimeoutUs());
2192 "%s using default PDO receive timeout of %d us",
2194 m_impl->ethercatManager.getPdoTimeoutUs());
2198 const uint32_t cycleNs =
static_cast<uint32_t
>(
std::llround(this->getPeriod() * 1e9));
2208 const int s = m_impl->firstSlave + int(j);
2210 auto e = m_impl->ethercatManager.readSDO<uint8_t>(s, 0x2012, 0x09, src);
2214 "%s: failed to read position loop source (joint %zu)",
2224 const int s = m_impl->firstSlave + int(j);
2226 auto e = m_impl->ethercatManager.readSDO<uint8_t>(s, 0x2011, 0x05, src);
2237 auto hasEnc1Pos = [&](
size_t j) {
2238 const int s = m_impl->firstSlave + int(j);
2241 auto hasEnc1Vel = [&](
size_t j) {
2242 const int s = m_impl->firstSlave + int(j);
2245 auto hasEnc2Pos = [&](
size_t j) {
2246 const int s = m_impl->firstSlave + int(j);
2249 auto hasEnc2Vel = [&](
size_t j) {
2250 const int s = m_impl->firstSlave + int(j);
2255 "%s using %zu axes, EtherCAT slaves %d to %d",
2259 m_impl->firstSlave +
int(m_impl->numAxes) - 1);
2265 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2267 m_impl->posLoopSrc[j] = readPosLoopSrc(j);
2268 m_impl->velLoopSrc[j] = readVelLoopSrc(j);
2276 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2278 auto bad = [&](
const char* what) {
2279 yCError(CIA402,
"%s j=%zu invalid configuration: %s", logPrefix, j, what);
2287 if (bad(
"pos_joint=enc1 but enc1 not mounted/mapped"))
2293 if (bad(
"pos_joint=enc2 but enc2 not mounted/mapped"))
2300 if (bad(
"pos_motor=enc1 but enc1 not mounted/mapped"))
2306 if (bad(
"pos_motor=enc2 but enc2 not mounted/mapped"))
2314 if (bad(
"vel_joint=enc1 but enc1 not mounted/mapped"))
2320 if (bad(
"vel_joint=enc2 but enc2 not mounted/mapped"))
2327 if (bad(
"vel_motor=enc1 but enc1 not mounted/mapped"))
2333 if (bad(
"vel_motor=enc2 but enc2 not mounted/mapped"))
2341 if (!m_impl->readEncoderResolutions())
2343 yCError(CIA402,
"%s failed to read encoder resolutions from SDO", logPrefix);
2346 if (!m_impl->readSiVelocityUnits())
2348 yCError(CIA402,
"%s failed to read velocity conversions from SDO", logPrefix);
2351 if (!m_impl->readGearRatios())
2353 yCError(CIA402,
"%s failed to read gear ratios from SDO", logPrefix);
2356 if (!m_impl->readMotorConstants())
2358 yCError(CIA402,
"%s failed to read motor constants from SDO", logPrefix);
2361 if (!m_impl->readTorqueValues())
2363 yCError(CIA402,
"%s failed to read torque values from SDO", logPrefix);
2368 uint16_t currentStrategy = 0;
2369 if (!m_impl->getPositionControlStrategy(currentStrategy))
2371 yCError(CIA402,
"%s failed to get current control strategy", logPrefix);
2375 "%s current control strategy is %u",
2377 static_cast<unsigned>(currentStrategy));
2381 "%s requested position strategy %u (%s)",
2383 static_cast<unsigned>(desiredPositionStrategy),
2384 useSimplePidMode ?
"simple PID" :
"cascaded PID");
2386 if (!m_impl->setPositionControlStrategy(desiredPositionStrategy))
2388 yCError(CIA402,
"%s failed to configure position control strategy", logPrefix);
2393 if (!m_impl->getPositionControlStrategy(currentStrategy))
2395 yCError(CIA402,
"%s failed to get current control strategy", logPrefix);
2399 "%s current control strategy after configuration is %u",
2401 static_cast<unsigned>(currentStrategy));
2403 const bool enableSimplePidGainsIo = (desiredPositionStrategy == kPositionStrategySimplePid);
2404 if (!enableSimplePidGainsIo && programSimplePidGains)
2407 "%s simple PID gains provided but position strategy is not simple PID; skipping "
2408 "0x2012 gains programming",
2412 if (enableSimplePidGainsIo && programSimplePidGains)
2414 if (!m_impl->configureSimplePidGains(simplePidKpNmPerDeg, simplePidKdNmSecPerDeg))
2416 yCError(CIA402,
"%s failed to program simple PID gains", logPrefix);
2419 }
else if (enableSimplePidGainsIo)
2422 "%s skipping simple PID gains programming (config keys not provided)",
2428 bool simplePidGainsAvailable =
false;
2429 if (enableSimplePidGainsIo)
2432 if (!m_impl->readSimplePidGains(readKp, readKd))
2434 yCError(CIA402,
"%s failed to read back simple PID gains", logPrefix);
2437 simplePidGainsAvailable =
true;
2439 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2442 "%s j=%zu simple PID gains: Kp=%.6f Nm/deg, Kd=%.6f Nm·s/deg",
2453 if (!extractListOfDoubleFromSearchable(cfg,
2454 "pos_limit_min_deg",
2455 m_impl->limits.minPositionLimitDeg))
2457 yCError(CIA402,
"%s failed to parse pos_limit_min_deg", logPrefix);
2460 if (!extractListOfDoubleFromSearchable(cfg,
2461 "pos_limit_max_deg",
2462 m_impl->limits.maxPositionLimitDeg))
2464 yCError(CIA402,
"%s failed to parse pos_limit_max_deg", logPrefix);
2467 if (!extractListOfBoolFromSearchable(cfg,
2468 "use_position_limits_from_config",
2469 m_impl->limits.usePositionLimitsFromConfig))
2471 yCError(CIA402,
"%s failed to parse use_position_limits_from_config", logPrefix);
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)
2480 "%s position limit lists must have exactly %zu elements",
2486 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2488 const bool inv = m_impl->invertedMotionSenseDirection[j];
2490 if (m_impl->limits.usePositionLimitsFromConfig[j])
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]);
2498 int32_t minCounts = 0;
2499 int32_t maxCounts = 0;
2502 minCounts = lowerCounts;
2503 maxCounts = upperCounts;
2507 minCounts = -upperCounts;
2508 maxCounts = -lowerCounts;
2511 if (!m_impl->setPositionCountsLimits(j, minCounts, maxCounts))
2513 yCError(CIA402,
"%s j=%zu failed to set position limits", logPrefix, j);
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);
2527 yCError(CIA402,
"%s j=%zu failed to read position limits from SDO", logPrefix, j);
2532 double minDeg = 0.0;
2533 double maxDeg = 0.0;
2536 minDeg = m_impl->targetCountsToJointDeg(j, minCounts);
2537 maxDeg = m_impl->targetCountsToJointDeg(j, maxCounts);
2541 minDeg = m_impl->targetCountsToJointDeg(j, maxCounts);
2542 maxDeg = m_impl->targetCountsToJointDeg(j, minCounts);
2545 m_impl->limits.minPositionLimitDeg[j] = minDeg;
2546 m_impl->limits.maxPositionLimitDeg[j] = maxDeg;
2553 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2555 const int slave = m_impl->firstSlave +
static_cast<int>(j);
2556 auto* rx = m_impl->ethercatManager.getRxPDO(slave);
2559 yCError(CIA402,
"%s invalid slave index %d for axis %zu", logPrefix, slave, j);
2562 rx->Controlword = 0x0000;
2569 yCError(CIA402,
"%s initial EtherCAT send/receive after SDO reading failed", logPrefix);
2576 for (
int j = 0; j < m_impl->numAxes; ++j)
2578 if (!m_impl->setPositionWindowDeg(j, positionWindowDeg[j], timingWindowMs[j]))
2580 yCError(CIA402,
"%s j=%d failed to set position window", logPrefix, j);
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);
2605 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2607 m_impl->sm[j] = std::make_unique<CiA402::StateMachine>();
2608 m_impl->sm[j]->reset();
2612 if (!extractListOfStringFromSearchable(cfg,
"axes_names", {}, m_impl->variables.jointNames))
2615 constexpr double initialPositionVelocityDegs = 10;
2616 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2621 m_impl->ppState.ppRefSpeedDegS[j] = initialPositionVelocityDegs;
2623 m_impl->setSDORefSpeed(j, initialPositionVelocityDegs);
2626 yCInfo(CIA402,
"%s opened %zu axes, initialization complete", logPrefix, m_impl->numAxes);
2632 const auto opErr = m_impl->ethercatManager.goOperational();
2635 yCError(CIA402,
"%s failed to enter OPERATIONAL state", logPrefix);
2642 = m_impl->ethercatManager.enableDCSync0(cycleNs, dcShiftNs);
2645 yCError(CIA402,
"%s failed to enable DC SYNC0", logPrefix);
2650 yWarning(
"%s DC synchronization disabled by configuration", logPrefix);
2661 yCError(CIA402,
"%s initial send/receive in OPERATIONAL failed", logPrefix);
2665 (void)m_impl->readFeedback();
2667 bool outOfLimits =
false;
2668 for (
size_t j = 0; j < m_impl->numAxes; ++j)
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];
2674 const bool belowMin = (posDeg < minDeg);
2675 const bool aboveMax = (posDeg > maxDeg);
2677 if (belowMin || aboveMax)
2679 const char* axisLabel =
nullptr;
2680 if (j < m_impl->variables.jointNames.size()
2681 && !m_impl->variables.jointNames[j].empty())
2683 axisLabel = m_impl->variables.jointNames[j].c_str();
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.",
2691 axisLabel ?
" (" :
"",
2692 axisLabel ? axisLabel :
"",
2693 axisLabel ?
")" :
"",
2704 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2706 const int slave = m_impl->firstSlave +
static_cast<int>(j);
2707 auto* rx = m_impl->ethercatManager.getRxPDO(slave);
2710 rx->Controlword = 0x0000;
2715 (void)m_impl->ethercatManager.sendReceive();
2725 yCError(CIA402,
"%s failed to start device thread", logPrefix);
2730 "%s device thread started (position strategy=%u: %s)",
2732 static_cast<unsigned>(desiredPositionStrategy),
2733 useSimplePidMode ?
"simple PID" :
"cascaded PID");
2735 if (simplePidGainsAvailable)
2737 yCInfo(CIA402,
"%s simple PID gains:", logPrefix);
2738 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2740 const char* axisLabel =
nullptr;
2741 if (j < m_impl->variables.jointNames.size() && !m_impl->variables.jointNames[j].empty())
2743 axisLabel = m_impl->variables.jointNames[j].c_str();
2746 const char*
open = axisLabel ?
" (" :
"";
2747 const char* label = axisLabel ? axisLabel :
"";
2748 const char*
close = axisLabel ?
")" :
"";
2751 "%s j=%zu%s%s%s Kp=%.6f Nm/deg, Kd=%.6f Nm\xC2\xB7s/deg",
2786 constexpr auto logPrefix =
"[run]";
2798 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2800 const int slaveIdx = m_impl->firstSlave +
static_cast<int>(j);
2802 auto tx = m_impl->ethercatManager.getTxView(slaveIdx);
2804 const int tgt = m_impl->controlModeState.target[j];
2807 if (m_impl->controlModeState.active[j] == VOCAB_CM_HW_FAULT
2808 && tgt == VOCAB_CM_FORCE_IDLE)
2810 const auto cmd = m_impl->sm[j]->faultReset();
2814 m_impl->setPoints.reset((
int)j);
2815 m_impl->velLatched[j] = m_impl->trqLatched[j] = m_impl->currLatched[j] =
false;
2835 if (cmd.writeOpMode)
2845 m_impl->setSetPoints();
2853 "%s sendReceive() failed, expected_wkc=%d got_wkc=%d",
2855 m_impl->ethercatManager.getExpectedWorkingCounter(),
2856 m_impl->ethercatManager.getWorkingCounter());
2857 m_impl->ethercatManager.dumpDiagnostics();
2863 m_impl->readFeedback();
2871 for (
size_t j = 0; j < m_impl->numAxes; ++j)
2873 const int slaveIdx = m_impl->firstSlave +
static_cast<int>(j);
2874 auto tx = m_impl->ethercatManager.getTxView(slaveIdx);
2875 bool flavourChanged =
false;
2888 int newActive = VOCAB_CM_IDLE;
2891 newActive = VOCAB_CM_HW_FAULT;
2892 }
else if (!hwInhibit && enabled)
2894 const int activeOp = m_impl->sm[j]->getActiveOpMode();
2900 int flavor = m_impl->controlModeState.cstFlavor[j];
2902 if (flavor != VOCAB_CM_CURRENT && flavor != VOCAB_CM_TORQUE)
2904 flavor = VOCAB_CM_TORQUE;
2910 = (flavor != m_impl->controlModeState.prevCstFlavor[j])
2911 || (m_impl->controlModeState.prevCstFlavor[j] == VOCAB_CM_UNKNOWN);
2920 if (newActive == VOCAB_CM_IDLE || newActive == VOCAB_CM_HW_FAULT
2921 || newActive == VOCAB_CM_FORCE_IDLE)
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;
2928 m_impl->controlModeState.target[j] = VOCAB_CM_IDLE;
2933 if (m_impl->controlModeState.active[j] != newActive || flavourChanged)
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);
2941 m_impl->controlModeState.active[j] = newActive;
2942 m_impl->controlModeState.prevCstFlavor[j] = m_impl->controlModeState.cstFlavor[j];
2947 constexpr double printingIntervalSec = 30.0;
2951 m_impl->runTimeAccumSec += dtSec;
2952 m_impl->runTimeSamples += 1;
2953 const auto windowSec
2956 if (windowSec >= printingIntervalSec)
2959 = (m_impl->runTimeSamples > 0)
2960 ? (m_impl->runTimeAccumSec /
static_cast<double>(m_impl->runTimeSamples)) * 1000.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)",
2967 printingIntervalSec,
2969 (m_impl->runTimeSamples > 0) ? (1000.0 / avgMs) : 0.0,
2970 m_impl->runTimeSamples,
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;
2991 *num =
static_cast<int>(m_impl->numAxes);
2997 yCError(CIA402,
"%s: resetMotorEncoder() not implemented",
Impl::kClassName.data());
3003 yCError(CIA402,
"%s: resetMotorEncoders() not implemented",
Impl::kClassName.data());
3010 "%s: setMotorEncoderCountsPerRevolution() not implemented",
3017 yCError(CIA402,
"%s: setMotorEncoder() not implemented",
Impl::kClassName.data());
3023 yCError(CIA402,
"%s: setMotorEncoders() not implemented",
Impl::kClassName.data());
3034 if (m >=
static_cast<int>(m_impl->numAxes))
3045 *cpr =
static_cast<double>(m_impl->enc1Res[m]);
3047 *cpr =
static_cast<double>(m_impl->enc2Res[m]);
3061 if (m >=
static_cast<int>(m_impl->numAxes))
3068 *v = m_impl->variables.motorEncoders[m];
3075 if (encs ==
nullptr)
3082 std::memcpy(encs, m_impl->variables.motorEncoders.data(), m_impl->numAxes *
sizeof(
double));
3090 if (encs ==
nullptr || time ==
nullptr)
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));
3105 if (encs ==
nullptr || time ==
nullptr)
3110 if (m >=
static_cast<int>(m_impl->numAxes))
3117 *encs = m_impl->variables.motorEncoders[m];
3118 *time = m_impl->variables.feedbackTime[m];
3130 if (m >=
static_cast<int>(m_impl->numAxes))
3137 *sp = m_impl->variables.motorVelocities[m];
3144 if (spds ==
nullptr)
3152 m_impl->variables.motorVelocities.data(),
3153 m_impl->numAxes *
sizeof(
double));
3165 if (m >=
static_cast<int>(m_impl->numAxes))
3172 *acc = m_impl->variables.motorAccelerations[m];
3179 if (accs ==
nullptr)
3187 m_impl->variables.motorAccelerations.data(),
3188 m_impl->numAxes *
sizeof(
double));
3198 if (encs ==
nullptr || time ==
nullptr)
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));
3215 if (encs ==
nullptr || time ==
nullptr)
3220 if (j >=
static_cast<int>(m_impl->numAxes))
3227 *encs = m_impl->variables.jointPositions[j];
3228 *time = m_impl->variables.feedbackTime[j];
3240 *ax =
static_cast<int>(m_impl->numAxes);
3246 yCError(CIA402,
"%s: resetEncoder() not implemented",
Impl::kClassName.data());
3252 yCError(CIA402,
"%s: resetEncoders() not implemented",
Impl::kClassName.data());
3258 yCError(CIA402,
"%s: setEncoder() not implemented",
Impl::kClassName.data());
3264 yCError(CIA402,
"%s: setEncoders() not implemented",
Impl::kClassName.data());
3275 if (j >=
static_cast<int>(m_impl->numAxes))
3282 *v = m_impl->variables.jointPositions[j];
3289 if (encs ==
nullptr)
3297 m_impl->variables.jointPositions.data(),
3298 m_impl->numAxes *
sizeof(
double));
3310 if (j >=
static_cast<int>(m_impl->numAxes))
3317 *sp = m_impl->variables.jointVelocities[j];
3324 if (spds ==
nullptr)
3332 m_impl->variables.jointVelocities.data(),
3333 m_impl->numAxes *
sizeof(
double));
3340 if (spds ==
nullptr)
3345 if (j >=
static_cast<int>(m_impl->numAxes))
3352 *spds = m_impl->variables.jointAccelerations[j];
3359 if (accs ==
nullptr)
3367 m_impl->variables.jointAccelerations.data(),
3368 m_impl->numAxes *
sizeof(
double));
3379 if (j >=
static_cast<int>(m_impl->numAxes))
3388 name = m_impl->variables.jointNames[j];
3394 if (axis >=
static_cast<int>(m_impl->numAxes))
3396 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), axis);
3399 type = yarp::dev::JointTypeEnum::VOCAB_JOINTTYPE_REVOLUTE;
3407 if (mode ==
nullptr)
3412 if (j >=
static_cast<int>(m_impl->numAxes))
3420 *mode = m_impl->controlModeState.active[j];
3427 if (modes ==
nullptr)
3435 std::memcpy(modes, m_impl->controlModeState.active.data(), m_impl->numAxes *
sizeof(
int));
3442 if (modes ==
nullptr || joints ==
nullptr)
3449 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n);
3455 for (
int k = 0; k < n; ++k)
3457 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
3459 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
3462 modes[k] = m_impl->controlModeState.active[joints[k]];
3470 if (j >=
static_cast<int>(m_impl->numAxes))
3477 yCError(CIA402,
"%s: control mode %d not supported",
Impl::kClassName.data(), mode);
3482 m_impl->controlModeState.target[j] = mode;
3483 if (mode == VOCAB_CM_CURRENT || mode == VOCAB_CM_TORQUE)
3485 m_impl->controlModeState.cstFlavor[j] = mode;
3493 if (modes ==
nullptr || joints ==
nullptr)
3500 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n);
3504 for (
int k = 0; k < n; ++k)
3506 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
3508 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
3511 m_impl->controlModeState.target[joints[k]] = modes[k];
3513 if (modes[k] == VOCAB_CM_CURRENT || modes[k] == VOCAB_CM_TORQUE)
3515 m_impl->controlModeState.cstFlavor[joints[k]] = modes[k];
3523 if (modes ==
nullptr)
3529 std::memcpy(m_impl->controlModeState.target.data(), modes, m_impl->numAxes *
sizeof(
int));
3531 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3533 if (m_impl->controlModeState.target[j] == VOCAB_CM_CURRENT
3534 || m_impl->controlModeState.target[j] == VOCAB_CM_TORQUE)
3536 m_impl->controlModeState.cstFlavor[j] = m_impl->controlModeState.target[j];
3551 if (j >=
static_cast<int>(m_impl->numAxes))
3558 *t = m_impl->variables.jointTorques[j];
3573 std::memcpy(t, m_impl->variables.jointTorques.data(), m_impl->numAxes *
sizeof(
double));
3585 if (j >=
static_cast<int>(m_impl->numAxes))
3592 *t = m_impl->setPoints.jointTorques[j];
3606 std::memcpy(t, m_impl->setPoints.jointTorques.data(), m_impl->numAxes *
sizeof(
double));
3613 if (j >=
static_cast<int>(m_impl->numAxes))
3622 if (m_impl->controlModeState.active[j] != VOCAB_CM_TORQUE)
3625 "%s: setRefTorque rejected: TORQUE mode is not active for the joint %d",
3633 m_impl->setPoints.jointTorques[j] = t;
3634 m_impl->setPoints.hasTorqueSP[j] =
true;
3648 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3650 if (m_impl->controlModeState.active[j] != VOCAB_CM_TORQUE)
3653 "%s: setRefTorques rejected: TORQUE mode is not active for the joint "
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);
3670 if (t ==
nullptr || joints ==
nullptr)
3677 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n_joint);
3684 for (
int k = 0; k < n_joint; ++k)
3686 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
3688 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
3691 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_TORQUE)
3694 "%s: setRefTorques rejected: TORQUE mode is not active for the joint %d",
3703 for (
int k = 0; k < n_joint; ++k)
3705 m_impl->setPoints.jointTorques[joints[k]] = t[k];
3706 m_impl->setPoints.hasTorqueSP[joints[k]] =
true;
3713 if (min ==
nullptr || max ==
nullptr)
3718 if (j >=
static_cast<int>(m_impl->numAxes))
3725 *min = -m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3726 *max = m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3733 if (min ==
nullptr || max ==
nullptr)
3739 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3741 min[j] = -m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3742 max[j] = m_impl->maxMotorTorqueNm[j] * m_impl->gearRatio[j];
3749 if (j >=
static_cast<int>(m_impl->numAxes))
3758 if (m_impl->controlModeState.active[j] != VOCAB_CM_VELOCITY)
3761 "%s: velocityMove rejected: VELOCITY mode is not active for the joint %d",
3771 m_impl->setPoints.jointVelocities[j] = spd;
3772 m_impl->setPoints.hasVelSP[j] =
true;
3778 if (spds ==
nullptr)
3787 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3789 if (m_impl->controlModeState.active[j] != VOCAB_CM_VELOCITY)
3792 "%s: velocityMove rejected: VELOCITY mode is not active for the joint "
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);
3814 if (joint >=
static_cast<int>(m_impl->numAxes))
3816 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joint);
3821 *vel = m_impl->setPoints.jointVelocities[joint];
3828 if (spds ==
nullptr)
3836 m_impl->setPoints.jointVelocities.data(),
3837 m_impl->numAxes *
sizeof(
double));
3844 if (vels ==
nullptr || joints ==
nullptr)
3851 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n_joint);
3857 for (
int k = 0; k < n_joint; ++k)
3859 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
3861 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
3864 vels[k] = m_impl->setPoints.jointVelocities[joints[k]];
3876 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
3878 yCError(CIA402,
"%s: setRefAcceleration: joint %d out of range",
Impl::kClassName.data(), j);
3885 accDegS2 = -accDegS2;
3889 constexpr double maxAcc = 10.0;
3890 if (accDegS2 > maxAcc)
3893 "%s: setRefAcceleration: joint %d: acceleration %.2f deg/s^2 too high, "
3894 "saturating to %.2f deg/s^2",
3903 int controlMode = -1;
3906 controlMode = m_impl->controlModeState.active[j];
3909 if (controlMode != VOCAB_CM_POSITION)
3915 const int s = m_impl->firstSlave + j;
3916 const int32_t acc =
static_cast<int32_t
>(
std::llround(accDegS2 * m_impl->degSToVel[j]));
3919 m_impl->ppState.ppRefAccelerationDegSS[j] = accDegS2;
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);
3934 yCError(CIA402,
"%s: setRefAccelerations: null pointer",
Impl::kClassName.data());
3938 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3952 if (j >=
static_cast<int>(m_impl->numAxes))
3958 int controlMode = -1;
3961 controlMode = m_impl->controlModeState.active[j];
3964 if (controlMode == VOCAB_CM_POSITION)
3968 *acc = m_impl->ppState.ppRefAccelerationDegSS[j];
3978 if (accs ==
nullptr)
3984 for (
size_t j = 0; j < m_impl->numAxes; ++j)
3986 int controlMode = -1;
3989 controlMode = m_impl->controlModeState.active[j];
3992 if (controlMode == VOCAB_CM_POSITION)
3996 accs[j] = m_impl->ppState.ppRefAccelerationDegSS[j];
4011 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4013 yCError(CIA402,
"%s: stop: joint %d out of range",
Impl::kClassName.data(), j);
4017 int controlMode = -1;
4020 controlMode = m_impl->controlModeState.active[j];
4023 if (controlMode == VOCAB_CM_POSITION)
4026 m_impl->ppState.ppHaltRequested[j] =
true;
4033 m_impl->setPoints.jointVelocities[j] = 0.0;
4034 m_impl->setPoints.hasVelSP[j] =
true;
4044 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4046 if (m_impl->controlModeState.active[j] == VOCAB_CM_POSITION)
4049 m_impl->ppState.ppHaltRequested[j] =
true;
4055 std::fill(m_impl->setPoints.jointVelocities.begin(),
4056 m_impl->setPoints.jointVelocities.end(),
4058 std::fill(m_impl->setPoints.hasVelSP.begin(), m_impl->setPoints.hasVelSP.end(),
true);
4065 if (spds ==
nullptr || joints ==
nullptr)
4072 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n_joint);
4079 for (
int k = 0; k < n_joint; ++k)
4081 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
4083 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
4086 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_VELOCITY)
4089 "%s: velocityMove rejected: VELOCITY mode is not active for the joint "
4099 for (
int k = 0; k < n_joint; ++k)
4101 m_impl->setPoints.jointVelocities[joints[k]] = spds[k];
4102 m_impl->setPoints.hasVelSP[joints[k]] =
true;
4112 if (accs ==
nullptr || joints ==
nullptr)
4119 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n_joint);
4129 if (accs ==
nullptr || joints ==
nullptr)
4141 if (joints ==
nullptr)
4148 yCError(CIA402,
"%s: invalid number of joints %d",
Impl::kClassName.data(), n_joint);
4154 for (
int k = 0; k < n_joint; ++k)
4156 if (joints[k] >=
static_cast<int>(m_impl->numAxes))
4158 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
4161 m_impl->setPoints.jointVelocities[joints[k]] = 0.0;
4162 m_impl->setPoints.hasVelSP[joints[k]] =
true;
4170 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4172 yCError(CIA402,
"%s: getLastJointFault: joint %d out of range",
Impl::kClassName.data(), j);
4176 const int slave = m_impl->firstSlave + j;
4180 auto err = m_impl->ethercatManager.readSDO<uint16_t>(slave, 0x603F, 0x00, code);
4184 "%s: getLastJointFault: SDO read 0x603F:00 failed (joint %d)",
4190 fault =
static_cast<int>(code);
4191 message = m_impl->describe603F(code);
4195 char report[8] = {0};
4196 auto err2 = m_impl->ethercatManager.readSDO(slave, 0x203F, 0x01, report);
4201 while (len <
sizeof(report) && report[len] !=
'\0')
4207 bool printable =
true;
4210 const unsigned char c =
static_cast<unsigned char>(report[i]);
4211 if (c < 0x20 || c > 0x7E)
4220 message +=
" — report: ";
4221 message.
append(report, len);
4224 char hex[3 * 8 + 1] = {0};
4226 for (
std::size_t i = 0; i < len && pos <= static_cast<int>(
sizeof(hex)) - 3; ++i)
4230 static_cast<unsigned char>(report[i]),
4231 (i + 1 < len) ?
" " :
"");
4232 message +=
" — report: [";
4243 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4245 yCError(CIA402,
"%s: positionMove: joint %d out of range",
Impl::kClassName.data(), j);
4249 int controlMode = -1;
4252 controlMode = m_impl->controlModeState.active[j];
4255 if (controlMode != VOCAB_CM_POSITION)
4258 "%s: positionMove rejected: POSITION mode not active for joint %d",
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;
4284 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4285 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4288 "%s: positionMove rejected: POSITION mode not active on joint %zu",
4296 for (
size_t j = 0; j < m_impl->numAxes; ++j)
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;
4309 if (!joints || !refsDeg || n <= 0)
4316 for (
int k = 0; k < n; ++k)
4318 if (joints[k] < 0 || joints[k] >=
static_cast<int>(m_impl->numAxes))
4320 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION)
4323 "%s: positionMove rejected: POSITION mode not active on joint %d",
4331 for (
int k = 0; k < n; ++k)
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;
4345 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4349 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4352 "%s: relativeMove rejected: POSITION mode not active for joint %d",
4359 m_impl->setPoints.ppJointTargetsDeg[j] += deltaDeg;
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;
4373 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4374 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION)
4378 for (
size_t j = 0; j < m_impl->numAxes; ++j)
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;
4391 if (!joints || !deltasDeg || n <= 0)
4395 for (
int k = 0; k < n; ++k)
4396 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION)
4400 for (
int k = 0; k < n; ++k)
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;
4415 if (flag ==
nullptr)
4417 yCError(CIA402,
"%s: checkMotionDone: null pointer",
Impl::kClassName.data());
4421 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4423 yCError(CIA402,
"%s: checkMotionDone: joint %d out of range",
Impl::kClassName.data(), j);
4428 *flag = m_impl->variables.targetReached[j];
4434 if (flag ==
nullptr)
4436 yCError(CIA402,
"%s: checkMotionDone: null pointer",
Impl::kClassName.data());
4441 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4443 flag[j] = m_impl->variables.targetReached[j];
4451 if (!joints || !flag || n <= 0)
4454 for (
int k = 0; k < n; ++k)
4466 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4468 yCError(CIA402,
"%s: setRefSpeed: joint %d out of range",
Impl::kClassName.data(), j);
4476 cm = m_impl->controlModeState.active[j];
4478 if (cm != VOCAB_CM_POSITION)
4481 "%s: setRefSpeed: POSITION mode not active for joint %d, not writing SDO",
4490 m_impl->ppState.ppRefSpeedDegS[j] = spDegS;
4493 m_impl->setSDORefSpeed(j, spDegS);
4500 if (spDegS ==
nullptr)
4502 yCError(CIA402,
"%s: setRefSpeeds: null pointer",
Impl::kClassName.data());
4505 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4507 this->
setRefSpeed(
static_cast<int>(j), spDegS[j]);
4514 if (!joints || !spDegS || n <= 0)
4516 yCError(CIA402,
"%s: setRefSpeeds: invalid args",
Impl::kClassName.data());
4520 for (
int k = 0; k < n; ++k)
4529 if (!ref || j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4536 *ref = m_impl->ppState.ppRefSpeedDegS[j];
4543 yCError(CIA402,
"%s: getRefSpeeds: null pointer",
Impl::kClassName.data());
4547 std::memcpy(spds, m_impl->ppState.ppRefSpeedDegS.data(), m_impl->numAxes *
sizeof(
double));
4553 if (!joints || !spds || n <= 0)
4555 yCError(CIA402,
"%s: getRefSpeeds: invalid args",
Impl::kClassName.data());
4559 for (
int k = 0; k < n; ++k)
4561 spds[k] = m_impl->ppState.ppRefSpeedDegS[joints[k]];
4568 if (!ref || j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4570 yCError(CIA402,
"%s: getTargetPosition: invalid args",
Impl::kClassName.data());
4575 *ref = m_impl->setPoints.ppJointTargetsDeg[j];
4581 if (refs ==
nullptr)
4583 yCError(CIA402,
"%s: getTargetPositions: null pointer",
Impl::kClassName.data());
4588 std::memcpy(refs, m_impl->setPoints.ppJointTargetsDeg.data(), m_impl->numAxes *
sizeof(
double));
4594 if (!joints || !refs || n <= 0)
4596 yCError(CIA402,
"%s: getTargetPositions: invalid args",
Impl::kClassName.data());
4600 for (
int k = 0; k < n; ++k)
4602 refs[k] = m_impl->setPoints.ppJointTargetsDeg[joints[k]];
4611 if (j < 0 || j >=
static_cast<int>(m_impl->numAxes))
4613 yCError(CIA402,
"%s: setPosition: joint %d out of range",
Impl::kClassName.data(), j);
4619 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION_DIRECT)
4622 "%s: setPosition rejected: POSITION_DIRECT mode is not active for joint %d",
4630 m_impl->setPoints.positionDirectJointTargetsDeg[j] = refDeg;
4631 m_impl->setPoints.positionDirectTargetCounts[j]
4632 = m_impl->jointDegToTargetCounts(
static_cast<size_t>(j), refDeg);
4638 if (refs ==
nullptr)
4640 yCError(CIA402,
"%s: setPositions: null pointer",
Impl::kClassName.data());
4646 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4648 if (m_impl->controlModeState.active[j] != VOCAB_CM_POSITION_DIRECT)
4651 "%s: setPositions rejected: POSITION_DIRECT mode is not active for joint "
4661 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4663 m_impl->setPoints.positionDirectJointTargetsDeg[j] = refs[j];
4664 m_impl->setPoints.positionDirectTargetCounts[j]
4665 = m_impl->jointDegToTargetCounts(j, refs[j]);
4672 if (!joints || !refs)
4674 yCError(CIA402,
"%s: setPositions: null pointer",
Impl::kClassName.data());
4680 "%s: setPositions: invalid number of joints %d",
4688 for (
int k = 0; k < n_joint; ++k)
4690 if (joints[k] < 0 || joints[k] >=
static_cast<int>(m_impl->numAxes))
4693 "%s: setPositions: joint %d out of range",
4698 if (m_impl->controlModeState.active[joints[k]] != VOCAB_CM_POSITION_DIRECT)
4701 "%s: setPositions rejected: POSITION_DIRECT mode is not active for joint "
4711 for (
int k = 0; k < n_joint; ++k)
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]);
4725 yCError(CIA402,
"%s: getRefPosition: null pointer",
Impl::kClassName.data());
4728 if (joint < 0 || joint >=
static_cast<int>(m_impl->numAxes))
4730 yCError(CIA402,
"%s: getRefPosition: joint %d out of range",
Impl::kClassName.data(), joint);
4735 *ref = m_impl->setPoints.positionDirectJointTargetsDeg[joint];
4743 yCError(CIA402,
"%s: getRefPositions: null pointer",
Impl::kClassName.data());
4749 m_impl->setPoints.positionDirectJointTargetsDeg.data(),
4750 m_impl->numAxes *
sizeof(
double));
4756 if (!joints || !refs)
4758 yCError(CIA402,
"%s: getRefPositions: null pointer",
Impl::kClassName.data());
4764 "%s: getRefPositions: invalid number of joints %d",
4771 for (
int k = 0; k < n_joint; ++k)
4773 if (joints[k] < 0 || joints[k] >=
static_cast<int>(m_impl->numAxes))
4776 "%s: getRefPositions: joint %d out of range",
4781 refs[k] = m_impl->setPoints.positionDirectJointTargetsDeg[joints[k]];
4790 yCError(CIA402,
"%s: getNumberOfMotors: null pointer",
Impl::kClassName.data());
4793 *num = m_impl->numAxes;
4804 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
4810 *val = m_impl->variables.driveTemperatures[m];
4816 if (vals ==
nullptr)
4822 std::memcpy(vals, m_impl->variables.driveTemperatures.data(), m_impl->numAxes *
sizeof(
double));
4830 "%s: The getTemperatureLimit function is not implemented",
4839 "%s: The setTemperatureLimit function is not implemented",
4851 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
4856 *val = m_impl->gearRatio[m];
4863 yCError(CIA402,
"%s: The setGearboxRatio function is not implemented",
Impl::kClassName.data());
4869 if (curr ==
nullptr)
4874 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
4876 yCError(CIA402,
"%s: getCurrent: motor %d out of range",
Impl::kClassName.data(), m);
4880 *curr = m_impl->variables.motorCurrents[m];
4886 if (currs ==
nullptr)
4892 std::memcpy(currs, m_impl->variables.motorCurrents.data(), m_impl->numAxes *
sizeof(
double));
4898 if (min ==
nullptr || max ==
nullptr)
4900 yCError(CIA402,
"%s: getCurrentRange: null pointer",
Impl::kClassName.data());
4903 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
4905 yCError(CIA402,
"%s: getCurrentRange: motor %d out of range",
Impl::kClassName.data(), m);
4909 *min = -m_impl->maxCurrentsA[m];
4910 *max = m_impl->maxCurrentsA[m];
4916 if (min ==
nullptr || max ==
nullptr)
4918 yCError(CIA402,
"%s: getCurrentRanges: null pointer",
Impl::kClassName.data());
4922 for (
size_t m = 0; m < m_impl->numAxes; ++m)
4924 min[m] = -m_impl->maxCurrentsA[m];
4925 max[m] = m_impl->maxCurrentsA[m];
4932 if (currs ==
nullptr)
4934 yCError(CIA402,
"%s: setRefCurrents: null pointer",
Impl::kClassName.data());
4941 for (
size_t j = 0; j < m_impl->numAxes; ++j)
4943 if (m_impl->controlModeState.active[j] != VOCAB_CM_CURRENT)
4946 "%s: setRefCurrents rejected: CURRENT mode is not active for the joint "
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);
4963 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
4965 yCError(CIA402,
"%s: setRefCurrent: motor %d out of range",
Impl::kClassName.data(), m);
4972 if (m_impl->controlModeState.active[m] != VOCAB_CM_CURRENT)
4975 "%s: setRefCurrent rejected: CURRENT mode is not active for the joint %d",
4983 m_impl->setPoints.motorCurrents[m] = curr;
4984 m_impl->setPoints.hasCurrentSP[m] =
true;
4991 if (currs ==
nullptr || motors ==
nullptr)
4993 yCError(CIA402,
"%s: setRefCurrents: null pointer",
Impl::kClassName.data());
4999 "%s: setRefCurrents: invalid number of motors %d",
5004 for (
int k = 0; k < n_motor; ++k)
5006 if (motors[k] < 0 || motors[k] >=
static_cast<int>(m_impl->numAxes))
5009 "%s: setRefCurrents: motor %d out of range",
5019 for (
int k = 0; k < n_motor; ++k)
5021 if (m_impl->controlModeState.active[motors[k]] != VOCAB_CM_CURRENT)
5024 "%s: setRefCurrents rejected: CURRENT mode is not active for the joint %d",
5033 for (
int k = 0; k < n_motor; ++k)
5035 m_impl->setPoints.motorCurrents[motors[k]] = currs[k];
5036 m_impl->setPoints.hasCurrentSP[motors[k]] =
true;
5043 if (currs ==
nullptr)
5045 yCError(CIA402,
"%s: getRefCurrents: null pointer",
Impl::kClassName.data());
5050 std::memcpy(currs, m_impl->setPoints.motorCurrents.data(), m_impl->numAxes *
sizeof(
double));
5056 if (curr ==
nullptr)
5058 yCError(CIA402,
"%s: getRefCurrent: null pointer",
Impl::kClassName.data());
5061 if (m < 0 || m >=
static_cast<int>(m_impl->numAxes))
5063 yCError(CIA402,
"%s: getRefCurrent: motor %d out of range",
Impl::kClassName.data(), m);
5068 *curr = m_impl->setPoints.motorCurrents[m];
5074 if (axis < 0 || axis >=
static_cast<int>(m_impl->numAxes))
5076 yCError(CIA402,
"%s: setLimits: axis %d out of range",
Impl::kClassName.data(), axis);
5082 if (!(min < 0.0 || max < 0.0) && (min >= max))
5085 "%s: setLimits: invalid limits [min=%g, max=%g]",
5094 m_impl->limits.maxPositionLimitDeg[axis] = max;
5095 m_impl->limits.minPositionLimitDeg[axis] = min;
5100 const bool inv = m_impl->invertedMotionSenseDirection[axis];
5101 const bool lowerLimitDisabled = (min < 0.0);
5102 const bool upperLimitDisabled = (max < 0.0);
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);
5109 int32_t minCounts = 0;
5110 int32_t maxCounts = 0;
5123 return m_impl->setPositionCountsLimits(axis, minCounts, maxCounts);
5128 if (min ==
nullptr || max ==
nullptr)
5133 if (axis < 0 || axis >=
static_cast<int>(m_impl->numAxes))
5135 yCError(CIA402,
"%s: getLimits: axis %d out of range",
Impl::kClassName.data(), axis);
5140 *min = m_impl->limits.minPositionLimitDeg[axis];
5141 *max = m_impl->limits.maxPositionLimitDeg[axis];
5148 constexpr auto logPrefix =
"[setVelLimits] ";
5149 yCError(CIA402,
"%s: The setVelLimits function is not implemented", logPrefix);
5156 constexpr auto logPrefix =
"[getVelLimits] ";
5157 yCError(CIA402,
"%s: The getVelLimits function is not implemented", logPrefix);
5169 *mode = m_impl->dummyInteractionMode;
5175 yarp::dev::InteractionModeEnum* modes)
5177 if (!joints || !modes || n_joints <= 0)
5183 for (
int k = 0; k < n_joints; ++k)
5185 if (joints[k] < 0 || joints[k] >=
static_cast<int>(m_impl->numAxes))
5187 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
5190 modes[k] = m_impl->dummyInteractionMode;
5197 if (modes ==
nullptr)
5203 for (
size_t j = 0; j < m_impl->numAxes; ++j)
5205 modes[j] = m_impl->dummyInteractionMode;
5212 if (axis < 0 || axis >=
static_cast<int>(m_impl->numAxes))
5214 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), axis);
5220 "%s: The setInteractionMode function is not implemented",
5227 yarp::dev::InteractionModeEnum* modes)
5229 if (!joints || !modes || n_joints <= 0)
5235 for (
int k = 0; k < n_joints; ++k)
5237 if (joints[k] < 0 || joints[k] >=
static_cast<int>(m_impl->numAxes))
5239 yCError(CIA402,
"%s: joint %d out of range",
Impl::kClassName.data(), joints[k]);
5246 "%s: The setInteractionModes function is not implemented",
5253 if (modes ==
nullptr)
5260 "%s: The setInteractionModes function is not implemented",
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.
CiA402MotionControl()
Default constructor.
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)
@ 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)
Process Data Object written from master to slave (RxPDO).
int8_t OpMode
0x6060: Modes of operation
uint16_t Controlword
0x6040: Controlword
std::vector< int > prevCstFlavor
std::vector< int > active
std::vector< int > cstFlavor
void resize(std::size_t n)
std::vector< int > target
std::vector< double > minPositionLimitDeg
std::vector< double > maxPositionLimitDeg
std::vector< bool > usePositionLimitsFromConfig
std::vector< double > ppRefSpeedDegS
std::vector< double > ppRefAccelerationDegSS
std::vector< bool > ppHaltRequested
std::vector< bool > ppPulseHi
void resize(std::size_t n)
std::vector< bool > hasCurrentSP
std::vector< double > positionDirectJointTargetsDeg
std::vector< double > jointVelocities
std::vector< bool > ppHasPosSP
std::vector< double > ppJointTargetsDeg
std::vector< bool > hasTorqueSP
std::vector< bool > ppIsRelative
std::vector< bool > hasVelSP
std::vector< bool > ppPulseCoolDown
std::vector< int32_t > ppTargetCounts
std::vector< double > motorCurrents
std::vector< double > jointTorques
std::vector< int32_t > positionDirectTargetCounts
std::vector< uint8_t > STO
std::vector< double > driveTemperatures
std::vector< double > jointAccelerations
std::vector< double > feedbackTime
std::vector< std::string > jointNames
std::vector< double > motorCurrents
std::vector< double > jointTorques
std::vector< double > jointPositions
std::vector< bool > targetReached
std::vector< double > motorVelocities
std::vector< uint8_t > SBC
std::vector< double > jointVelocities
std::vector< double > motorEncoders
void resizeContainers(std::size_t numAxes)
std::vector< double > motorAccelerations
static constexpr std::string_view kClassName
std::vector< double > maxCurrentsA
bool setPositionControlStrategy(uint16_t strategyValue)
static int ciaOpToYarp(int op)
std::vector< double > velToDegS
ControlModeState controlModeState
std::vector< double > ratedMotorTorqueNm
std::vector< double > gearRatio
std::vector< Mount > enc2Mount
static std::string_view yarpToString(int op)
std::vector< VelSrc > velSrcMotor
std::vector< PosSrc > posSrcMotor
std::vector< bool > trqLatched
yarp::dev::InteractionModeEnum dummyInteractionMode
std::vector< double > gearRatioInv
bool setPositionWindowDeg(int j, double winDeg, double winTime_ms)
std::vector< VelSrc > velSrcJoint
std::mutex CiA402MotionControlMutex
std::size_t runTimeSamples
std::vector< bool > posLatched
static constexpr uint64_t TIMESTAMP_WRAP_PERIOD_US
std::vector< double > torqueSeedNm
static std::tuple< double, double, const char * > decode60A9(uint32_t v)
std::string describe603F(uint16_t code)
VariablesReadFromMotors variables
bool readSiVelocityUnits()
std::vector< bool > currLatched
static constexpr uint32_t TIMESTAMP_WRAP_HALF_RANGE
int32_t jointDegToTargetCounts(size_t j, double jointDeg) const
std::vector< uint32_t > tsLastRaw
std::vector< double > torqueConstants
std::chrono::steady_clock::time_point avgWindowStart
std::vector< Mount > enc1Mount
double loopCountsToJointDeg(std::size_t j, double counts) const
PositionProfileState ppState
std::vector< double > maxMotorTorqueNm
std::vector< double > enc2ResInv
std::vector< std::unique_ptr< CiA402::StateMachine > > sm
std::vector< uint32_t > enc2Res
std::vector< uint32_t > enc1Res
bool readMotorConstants()
std::vector< uint64_t > tsWraps
std::vector< double > degSToVel
void setSDORefSpeed(int j, double spDegS)
static int yarpToCiaOp(int cm)
std::vector< double > enc1ResInv
std::vector< int > lastActiveMode
bool readSimplePidGains(std::vector< double > &kpNmPerDeg, std::vector< double > &kdNmSecPerDeg)
struct yarp::dev::CiA402MotionControl::Impl::Limits limits
std::vector< SensorSrc > posLoopSrc
bool readEncoderResolutions()
std::vector< SensorSrc > velLoopSrc
std::vector< PosSrc > posSrcJoint
bool configureSimplePidGains(const std::vector< double > &kpNmPerDeg, const std::vector< double > &kdNmSecPerDeg)
::CiA402::EthercatManager ethercatManager
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)
std::vector< bool > invertedMotionSenseDirection
double targetCountsToJointDeg(size_t j, int32_t counts) const
std::vector< bool > velLatched