From 709fad8d3109ff7c072d9120acb4914218cd3202 Mon Sep 17 00:00:00 2001
From: Christian Dreher <c.dreher@kit.edu>
Date: Thu, 12 Dec 2024 11:26:18 +0100
Subject: [PATCH] refactor: Reflect hardware divergence by splutting shared
 code for ARMAR-DE and ARMAR-7

This change is to not make it look like the code of shape controllers is still shared between ARMAR-DE and ARMAR-7. The firmware diverged when it was decided to introduce magic numbers as PWM control targets to trigger certain control commands (instead of a dedicated boolean via PDO etc.) due to time constraints.

If the PDO is updated in the near future to model these control commands as booleans or enums or similar via PDOs, then the code can be merged again. The shape controller is a very high-level piece of software, and there is no reason to split the code other than the above-mentioned hardware-hack.
---
 .../devices/ethercat/hand/armar7/Device.cpp   |   2 +-
 .../hand/armar7/njoint_controller/Shape.cpp   |   3 +-
 .../hand/armar7/njoint_controller/Shape.h     |   4 +-
 .../ethercat/hand/armar7de/CMakeLists.txt     |   2 -
 .../ethercat/hand/armar7de/constants.h        |   2 -
 .../ethercat/hand/armarde/CMakeLists.txt      |   2 +
 .../devices/ethercat/hand/armarde/Device.cpp  |  10 +-
 .../njoint_controller/Shape.cpp               | 145 ++++++++----------
 .../njoint_controller/Shape.h                 |  42 ++---
 9 files changed, 97 insertions(+), 115 deletions(-)
 rename source/devices/ethercat/hand/{armar7de => armarde}/njoint_controller/Shape.cpp (73%)
 rename source/devices/ethercat/hand/{armar7de => armarde}/njoint_controller/Shape.h (79%)

diff --git a/source/devices/ethercat/hand/armar7/Device.cpp b/source/devices/ethercat/hand/armar7/Device.cpp
index 01256117..90f29c05 100644
--- a/source/devices/ethercat/hand/armar7/Device.cpp
+++ b/source/devices/ethercat/hand/armar7/Device.cpp
@@ -378,7 +378,7 @@ namespace devices::ethercat::hand::armar7
 
         armar7::ShapeControllerConfigPtr cfg = new armar7::ShapeControllerConfig(getDeviceName());
         wrapper->controller = armar7::ShapeControllerPtr::dynamicCast(
-            robotUnit->createNJointController(armar7de::constants::NJOINT_CONTROLLER_NAME,
+            robotUnit->createNJointController(std::string{controller_name},
                                               handName + "_NJointArmar7HandShapeController",
                                               cfg,
                                               false,
diff --git a/source/devices/ethercat/hand/armar7/njoint_controller/Shape.cpp b/source/devices/ethercat/hand/armar7/njoint_controller/Shape.cpp
index 8a32b43e..e4d4d258 100644
--- a/source/devices/ethercat/hand/armar7/njoint_controller/Shape.cpp
+++ b/source/devices/ethercat/hand/armar7/njoint_controller/Shape.cpp
@@ -12,8 +12,7 @@ namespace devices::ethercat::hand::armar7
 {
 
     armarx::NJointControllerRegistration<ShapeController>
-        registrationControllerNJointArmar7deHandShapeController(
-            armar7de::constants::NJOINT_CONTROLLER_NAME);
+        registrationControllerNJointArmar7deHandShapeController(std::string{controller_name});
 
     ShapeController::ShapeController(armarx::RobotUnitPtr prov,
                                      ShapeControllerConfigPtr config,
diff --git a/source/devices/ethercat/hand/armar7/njoint_controller/Shape.h b/source/devices/ethercat/hand/armar7/njoint_controller/Shape.h
index 46739d64..339404f1 100644
--- a/source/devices/ethercat/hand/armar7/njoint_controller/Shape.h
+++ b/source/devices/ethercat/hand/armar7/njoint_controller/Shape.h
@@ -20,6 +20,8 @@ namespace armarx
 namespace devices::ethercat::hand::armar7
 {
 
+    static constexpr std::string_view controller_name = "NJointArmar7HandShapeController";
+
     using ShapeControllerConfigPtr = IceUtil::Handle<class ShapeControllerConfig>;
 
     class ShapeControllerConfig : virtual public armarx::NJointControllerConfig
@@ -54,7 +56,7 @@ namespace devices::ethercat::hand::armar7
         std::string
         getClassName(const Ice::Current&) const override
         {
-            return armar7de::constants::NJOINT_CONTROLLER_NAME;
+            return std::string{controller_name};
         }
 
         void stopMotion();
diff --git a/source/devices/ethercat/hand/armar7de/CMakeLists.txt b/source/devices/ethercat/hand/armar7de/CMakeLists.txt
index 87ceb4a3..3c1c8925 100644
--- a/source/devices/ethercat/hand/armar7de/CMakeLists.txt
+++ b/source/devices/ethercat/hand/armar7de/CMakeLists.txt
@@ -15,7 +15,6 @@ armarx_add_library(hand_armar7de
         joint_controller/AbsolutePosition.cpp
         joint_controller/PWM.cpp
         joint_controller/StopMovement.cpp
-        njoint_controller/Shape.cpp
     HEADERS
         sub_device/absolute/Data.h
         sub_device/absolute/Config.h
@@ -26,7 +25,6 @@ armarx_add_library(hand_armar7de
         joint_controller/AbsolutePosition.h
         joint_controller/PWM.h
         joint_controller/StopMovement.h
-        njoint_controller/Shape.h
     DEPENDENCIES
         RobotAPIUnits
         armarx_control::ethercat
diff --git a/source/devices/ethercat/hand/armar7de/constants.h b/source/devices/ethercat/hand/armar7de/constants.h
index 560d7fc3..c27e501a 100644
--- a/source/devices/ethercat/hand/armar7de/constants.h
+++ b/source/devices/ethercat/hand/armar7de/constants.h
@@ -24,8 +24,6 @@
 namespace devices::ethercat::hand::armar7de::constants
 {
 
-    inline const std::string NJOINT_CONTROLLER_NAME = "NJointArmar7deHandShapeController";
-
     inline const std::string FINGERS = "Fingers";
     inline const std::string INDEX = "Index";
     inline const std::string THUMB_FLEXION = "ThumbFlexion";
diff --git a/source/devices/ethercat/hand/armarde/CMakeLists.txt b/source/devices/ethercat/hand/armarde/CMakeLists.txt
index 4d5b463f..51e3b78b 100644
--- a/source/devices/ethercat/hand/armarde/CMakeLists.txt
+++ b/source/devices/ethercat/hand/armarde/CMakeLists.txt
@@ -6,6 +6,7 @@ armarx_add_library(hand_armarde
         sub_device/absolute/Device.cpp
         sub_device/relative/Data.cpp
         sub_device/relative/Device.cpp
+        njoint_controller/Shape.cpp
         ErrorDecoder.cpp
         Slave.cpp
     HEADERS
@@ -16,6 +17,7 @@ armarx_add_library(hand_armarde
         sub_device/absolute/Device.h
         sub_device/relative/Data.h
         sub_device/relative/Device.h
+        njoint_controller/Shape.h
         ErrorDecoder.h
         Slave.h
         SlaveIO.h
diff --git a/source/devices/ethercat/hand/armarde/Device.cpp b/source/devices/ethercat/hand/armarde/Device.cpp
index 6b264e4c..26e0094a 100644
--- a/source/devices/ethercat/hand/armarde/Device.cpp
+++ b/source/devices/ethercat/hand/armarde/Device.cpp
@@ -17,7 +17,7 @@
 #include <devices/ethercat/hand/armar7de/constants.h>
 #include <devices/ethercat/hand/armar7de/joint_controller/PWM.h>
 #include <devices/ethercat/hand/armar7de/joint_controller/RelativePosition.h>
-#include <devices/ethercat/hand/armar7de/njoint_controller/Shape.h>
+#include <devices/ethercat/hand/armarde/njoint_controller/Shape.h>
 #include <devices/ethercat/hand/armarde/sub_device/absolute/Device.h>
 #include <devices/ethercat/hand/armarde/sub_device/relative/Device.h>
 #include <devices/ethercat/hand/common/AbstractHandControllerWrapper.h>
@@ -281,7 +281,7 @@ namespace devices::ethercat::hand::armarde
     {
 
     public:
-        armar7de::ShapeControllerPtr controller;
+        armarde::ShapeControllerPtr controller;
 
         HandControllerWrapperArmarde(VirtualRobot::RobotPtr robot,
                                      std::string handName,
@@ -366,9 +366,9 @@ namespace devices::ethercat::hand::armarde
         HandControllerWrapperArmardePtr wrapper(
             new HandControllerWrapperArmarde(robot, getDeviceName(), handEefName));
 
-        armar7de::ShapeControllerConfigPtr cfg = new armar7de::ShapeControllerConfig(getDeviceName());
-        wrapper->controller = armar7de::ShapeControllerPtr::dynamicCast(
-            robotUnit->createNJointController(armar7de::constants::NJOINT_CONTROLLER_NAME,
+        armarde::ShapeControllerConfigPtr cfg = new armarde::ShapeControllerConfig(getDeviceName());
+        wrapper->controller = armarde::ShapeControllerPtr::dynamicCast(
+            robotUnit->createNJointController(std::string{controller_name},
                                               handName + "_NJointArmardeHandShapeController",
                                               cfg,
                                               false,
diff --git a/source/devices/ethercat/hand/armar7de/njoint_controller/Shape.cpp b/source/devices/ethercat/hand/armarde/njoint_controller/Shape.cpp
similarity index 73%
rename from source/devices/ethercat/hand/armar7de/njoint_controller/Shape.cpp
rename to source/devices/ethercat/hand/armarde/njoint_controller/Shape.cpp
index 5adbc7a0..9724af7e 100644
--- a/source/devices/ethercat/hand/armar7de/njoint_controller/Shape.cpp
+++ b/source/devices/ethercat/hand/armarde/njoint_controller/Shape.cpp
@@ -8,71 +8,69 @@
 #include <devices/ethercat/hand/armar7de/joint_controller/AbsolutePosition.h>
 #include <devices/ethercat/hand/armar7de/joint_controller/PWM.h>
 
-
-namespace devices::ethercat::hand::armar7de
+namespace devices::ethercat::hand::armarde
 {
 
     armarx::NJointControllerRegistration<ShapeController>
-        registrationControllerNJointArmar7deHandShapeController(constants::NJOINT_CONTROLLER_NAME);
-
+        registrationControllerNJointArmar7deHandShapeController(std::string{controller_name});
 
     ShapeController::ShapeController(armarx::RobotUnitPtr prov,
                                      ShapeControllerConfigPtr config,
                                      const VirtualRobot::RobotPtr& r)
     {
         ARMARX_CHECK_EXPRESSION(prov);
-        auto thumbDeviceName = config->deviceName + constants::THUMB_FLEXION;
+        auto thumbDeviceName = config->deviceName + armar7de::constants::THUMB_FLEXION;
         armarx::ControlTargetBase* ct =
-            useControlTarget(thumbDeviceName, ctrl_modes::Armar7deHandPwm);
+            useControlTarget(thumbDeviceName, armar7de::ctrl_modes::Armar7deHandPwm);
         ARMARX_CHECK_EXPRESSION(ct) << "control target: " << thumbDeviceName;
         armarx::ConstSensorDevicePtr thumbSensor = peekSensorDevice(thumbDeviceName);
         ARMARX_CHECK_EXPRESSION(thumbSensor) << "device name: " << thumbDeviceName;
 
         thumbSensorValues =
-            thumbSensor->getSensorValue()->asA<sub_device::relative::SensorDataValue>();
+            thumbSensor->getSensorValue()->asA<armar7de::sub_device::relative::SensorDataValue>();
         ARMARX_CHECK_EXPRESSION(thumbSensorValues);
-        ARMARX_CHECK_EXPRESSION(ct->asA<PWMControlTarget>());
-        thumbFlexionControlTarget = ct->asA<PWMControlTarget>();
+        ARMARX_CHECK_EXPRESSION(ct->asA<armar7de::PWMControlTarget>());
+        thumbFlexionControlTarget = ct->asA<armar7de::PWMControlTarget>();
 
-        auto fingersDeviceName = config->deviceName + constants::FINGERS;
-        ct = useControlTarget(fingersDeviceName, ctrl_modes::Armar7deHandPwm);
+        auto fingersDeviceName = config->deviceName + armar7de::constants::FINGERS;
+        ct = useControlTarget(fingersDeviceName, armar7de::ctrl_modes::Armar7deHandPwm);
         ARMARX_CHECK_EXPRESSION(ct) << "control target: " << fingersDeviceName;
         armarx::ConstSensorDevicePtr fingersSensor = peekSensorDevice(fingersDeviceName);
         ARMARX_CHECK_EXPRESSION(fingersSensor) << "device name: " << fingersDeviceName;
 
         fingersSensorValues =
-            fingersSensor->getSensorValue()->asA<sub_device::relative::SensorDataValue>();
+            fingersSensor->getSensorValue()->asA<armar7de::sub_device::relative::SensorDataValue>();
         ARMARX_CHECK_EXPRESSION(fingersSensorValues);
-        ARMARX_CHECK_EXPRESSION(ct->asA<PWMControlTarget>());
-        fingersControlTarget = ct->asA<PWMControlTarget>();
+        ARMARX_CHECK_EXPRESSION(ct->asA<armar7de::PWMControlTarget>());
+        fingersControlTarget = ct->asA<armar7de::PWMControlTarget>();
 
-        auto indexDeviceName = config->deviceName + constants::INDEX;
-        ct = useControlTarget(indexDeviceName, ctrl_modes::Armar7deHandPwm);
+        auto indexDeviceName = config->deviceName + armar7de::constants::INDEX;
+        ct = useControlTarget(indexDeviceName, armar7de::ctrl_modes::Armar7deHandPwm);
         ARMARX_CHECK_EXPRESSION(ct) << "control target: " << indexDeviceName;
         armarx::ConstSensorDevicePtr indexSensor = peekSensorDevice(indexDeviceName);
         ARMARX_CHECK_EXPRESSION(indexSensor) << "device name: " << indexDeviceName;
 
         indexSensorValues =
-            indexSensor->getSensorValue()->asA<sub_device::relative::SensorDataValue>();
+            indexSensor->getSensorValue()->asA<armar7de::sub_device::relative::SensorDataValue>();
         ARMARX_CHECK_EXPRESSION(indexSensorValues);
-        ARMARX_CHECK_EXPRESSION(ct->asA<PWMControlTarget>());
-        indexControlTarget = ct->asA<PWMControlTarget>();
+        ARMARX_CHECK_EXPRESSION(ct->asA<armar7de::PWMControlTarget>());
+        indexControlTarget = ct->asA<armar7de::PWMControlTarget>();
 
-        auto thumbRotationDeviceName = config->deviceName + constants::THUMB_CIRCUMDUCTION;
+        auto thumbRotationDeviceName =
+            config->deviceName + armar7de::constants::THUMB_CIRCUMDUCTION;
         ct = useControlTarget(thumbRotationDeviceName, armarx::ControlModes::Position1DoF);
         ARMARX_CHECK_EXPRESSION(ct) << "control target: " << thumbRotationDeviceName;
         armarx::ConstSensorDevicePtr thumbRotationSensor =
             peekSensorDevice(thumbRotationDeviceName);
         ARMARX_CHECK_EXPRESSION(thumbRotationSensor) << "device name: " << thumbRotationDeviceName;
 
-        thumbRotationSensorValues =
-            thumbRotationSensor->getSensorValue()->asA<sub_device::absolute::SensorDataValue>();
+        thumbRotationSensorValues = thumbRotationSensor->getSensorValue()
+                                        ->asA<armar7de::sub_device::absolute::SensorDataValue>();
         ARMARX_CHECK_EXPRESSION(thumbRotationSensorValues);
-        ARMARX_CHECK_EXPRESSION(ct->asA<AbsolutePositionControlTarget>());
-        thumbCircumductionControlTarget = ct->asA<AbsolutePositionControlTarget>();
+        ARMARX_CHECK_EXPRESSION(ct->asA<armar7de::AbsolutePositionControlTarget>());
+        thumbCircumductionControlTarget = ct->asA<armar7de::AbsolutePositionControlTarget>();
     }
 
-
     void
     ShapeController::rtPreActivateController()
     {
@@ -82,19 +80,18 @@ namespace devices::ethercat::hand::armar7de
         this->thumbCircumductionTarget = thumbRotationSensorValues->position;
     }
 
-
     void
     ShapeController::stopMotion()
     {
         enableControl = false;
     }
 
-
     void
-    ShapeController::setConfigs(const sub_device::relative::DataConfig& fingersConfig,
-                                const sub_device::relative::DataConfig& indexConfig,
-                                const sub_device::relative::DataConfig& thumbConfig,
-                                const sub_device::absolute::DataConfig& thumbRotationConfig)
+    ShapeController::setConfigs(
+        const armar7de::sub_device::relative::DataConfig& fingersConfig,
+        const armar7de::sub_device::relative::DataConfig& indexConfig,
+        const armar7de::sub_device::relative::DataConfig& thumbConfig,
+        const armar7de::sub_device::absolute::DataConfig& thumbRotationConfig)
     {
         fingersMaxPwm = fingersConfig.maxPwm;
         indexMaxPwm = indexConfig.maxPwm;
@@ -112,28 +109,24 @@ namespace devices::ethercat::hand::armar7de
         thumbRotationPwmLimit = thumbRotationMaxPwm;
     }
 
-
     std::int16_t
     ShapeController::getFingersPwm()
     {
         return fingersPwm;
     }
 
-
     std::int16_t
     ShapeController::getIndexPwm()
     {
         return indexPwm;
     }
 
-
     std::int16_t
     ShapeController::getThumbPwm()
     {
         return thumbPwm;
     }
 
-
     // std::int16_t
     // ShapeController::getThumbRotationPwm()
     // {
@@ -147,63 +140,54 @@ namespace devices::ethercat::hand::armar7de
         return fingersTarget;
     }
 
-
     float
     ShapeController::getIndexTarget()
     {
         return indexTarget;
     }
 
-
     float
     ShapeController::getThumbTarget()
     {
         return thumbFlexionTarget;
     }
 
-
     float
     ShapeController::getThumbCircumductionTarget()
     {
         return thumbCircumductionTarget;
     }
 
-
     float
     ShapeController::getFingersJointValue() const
     {
         return actualFingersJointValue;
     }
 
-
     float
     ShapeController::getIndexJointValue() const
     {
         return actualIndexJointValue;
     }
 
-
     float
     ShapeController::getThumbFlexionValue() const
     {
         return actualThumbJointValue;
     }
 
-
     float
     ShapeController::getThumbRotationJointValue() const
     {
         return actualThumbRotationJointValue;
     }
 
-
     bool
     ShapeController::isControlEnabled()
     {
         return enableControl;
     }
 
-
     void
     ShapeController::rtRun(const IceUtil::Time& /*sensorValuesTimestamp*/,
                            const IceUtil::Time& /*timeSinceLastIteration*/)
@@ -249,70 +233,70 @@ namespace devices::ethercat::hand::armar7de
         thumbCircumductionControlTarget->maxPWM = thumbRotationMaxPwm;
     }
 
-
     armarx::WidgetDescription::StringWidgetDictionary
     ShapeController::getFunctionDescriptions(const Ice::Current&) const
     {
         using namespace armarx::WidgetDescription;
         HBoxLayoutPtr hbox = new HBoxLayout;
         {
-            hbox->children.emplace_back(new Label(false, constants::FINGERS));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::FINGERS));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::FINGERS;
+            slider->name = armar7de::constants::FINGERS;
             slider->min = 0;
             slider->defaultValue = getFingersJointValue();
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::INDEX));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::INDEX));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::INDEX;
+            slider->name = armar7de::constants::INDEX;
             slider->min = 0;
             slider->defaultValue = getIndexJointValue();
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::THUMB_FLEXION));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::THUMB_FLEXION));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::THUMB_FLEXION;
+            slider->name = armar7de::constants::THUMB_FLEXION;
             slider->min = 0;
             slider->defaultValue = getThumbFlexionValue();
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::THUMB_CIRCUMDUCTION));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::THUMB_CIRCUMDUCTION));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::THUMB_CIRCUMDUCTION;
+            slider->name = armar7de::constants::THUMB_CIRCUMDUCTION;
             slider->min = 0;
             slider->defaultValue = getThumbRotationJointValue();
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::FINGERS + "MaxPwm"));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::FINGERS + "MaxPwm"));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::FINGERS + "MaxPwm";
+            slider->name = armar7de::constants::FINGERS + "MaxPwm";
             slider->min = 0;
             slider->defaultValue = 1;
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::INDEX + "MaxPwm"));
+            hbox->children.emplace_back(new Label(false, armar7de::constants::INDEX + "MaxPwm"));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::INDEX + "MaxPwm";
+            slider->name = armar7de::constants::INDEX + "MaxPwm";
             slider->min = 0;
             slider->defaultValue = 1;
             slider->max = 1;
             hbox->children.emplace_back(slider);
         }
         {
-            hbox->children.emplace_back(new Label(false, constants::THUMB_FLEXION + "MaxPwm"));
+            hbox->children.emplace_back(
+                new Label(false, armar7de::constants::THUMB_FLEXION + "MaxPwm"));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::THUMB_FLEXION + "MaxPwm";
+            slider->name = armar7de::constants::THUMB_FLEXION + "MaxPwm";
             slider->min = 0;
             slider->defaultValue = 1;
             slider->max = 1;
@@ -320,9 +304,9 @@ namespace devices::ethercat::hand::armar7de
         }
         {
             hbox->children.emplace_back(
-                new Label(false, constants::THUMB_CIRCUMDUCTION + "MaxPwm"));
+                new Label(false, armar7de::constants::THUMB_CIRCUMDUCTION + "MaxPwm"));
             FloatSliderPtr slider = new FloatSlider;
-            slider->name = constants::THUMB_CIRCUMDUCTION + "MaxPwm";
+            slider->name = armar7de::constants::THUMB_CIRCUMDUCTION + "MaxPwm";
             slider->min = 0;
             slider->defaultValue = 1;
             slider->max = 1;
@@ -332,7 +316,6 @@ namespace devices::ethercat::hand::armar7de
         return {{"Targets", hbox}};
     }
 
-
     void
     ShapeController::callDescribedFunction(const std::string& name,
                                            const armarx::StringVariantBaseMap& valueMap,
@@ -349,10 +332,10 @@ namespace devices::ethercat::hand::armar7de
                 maxPwm[joint] = valueMap.at(joint + "MaxPwm")->getFloat();
             };
 
-            setJoint(constants::FINGERS);
-            setJoint(constants::INDEX);
-            setJoint(constants::THUMB_FLEXION);
-            setJoint(constants::THUMB_CIRCUMDUCTION);
+            setJoint(armar7de::constants::FINGERS);
+            setJoint(armar7de::constants::INDEX);
+            setJoint(armar7de::constants::THUMB_FLEXION);
+            setJoint(armar7de::constants::THUMB_CIRCUMDUCTION);
 
             setTargetsWithPwmMap(targets, maxPwm);
         }
@@ -393,12 +376,11 @@ namespace devices::ethercat::hand::armar7de
             }
         };
 
-        setTargetIfPresent(constants::FINGERS, this->fingersTarget, 1.f);
-        setTargetIfPresent(constants::INDEX, this->indexTarget, 1.f);
-        setTargetIfPresent(constants::THUMB_FLEXION, this->thumbFlexionTarget, 1.f);
+        setTargetIfPresent(armar7de::constants::FINGERS, this->fingersTarget, 1.f);
+        setTargetIfPresent(armar7de::constants::INDEX, this->indexTarget, 1.f);
+        setTargetIfPresent(armar7de::constants::THUMB_FLEXION, this->thumbFlexionTarget, 1.f);
         setTargetIfPresent(
-            constants::THUMB_CIRCUMDUCTION, this->thumbCircumductionTarget, M_PI_2);
-
+            armar7de::constants::THUMB_CIRCUMDUCTION, this->thumbCircumductionTarget, M_PI_2);
 
         const auto setPWMIfPresent =
             [&maxPWM](const std::string& name, std::uint16_t& value, std::uint16_t pwmLimit)
@@ -411,11 +393,12 @@ namespace devices::ethercat::hand::armar7de
             }
         };
 
-        setPWMIfPresent(constants::FINGERS, this->fingersMaxPwm, fingersPwmLimit);
-        setPWMIfPresent(constants::INDEX, this->indexMaxPwm, indexPwmLimit);
-        setPWMIfPresent(constants::THUMB_FLEXION, this->thumbMaxPwm, thumbPwmLimit);
-        setPWMIfPresent(
-            constants::THUMB_CIRCUMDUCTION, this->thumbRotationMaxPwm, thumbRotationPwmLimit);
+        setPWMIfPresent(armar7de::constants::FINGERS, this->fingersMaxPwm, fingersPwmLimit);
+        setPWMIfPresent(armar7de::constants::INDEX, this->indexMaxPwm, indexPwmLimit);
+        setPWMIfPresent(armar7de::constants::THUMB_FLEXION, this->thumbMaxPwm, thumbPwmLimit);
+        setPWMIfPresent(armar7de::constants::THUMB_CIRCUMDUCTION,
+                        this->thumbRotationMaxPwm,
+                        thumbRotationPwmLimit);
 
         enableControl = true;
     }
@@ -467,11 +450,11 @@ namespace devices::ethercat::hand::armar7de
     ShapeController::getJointValues(const Ice::Current&)
     {
         std::map<std::string, float> values;
-        values[constants::FINGERS] = actualFingersJointValue;
-        values[constants::INDEX] = actualIndexJointValue;
-        values[constants::THUMB_FLEXION] = actualThumbJointValue;
-        values[constants::THUMB_CIRCUMDUCTION] = actualThumbRotationJointValue;
+        values[armar7de::constants::FINGERS] = actualFingersJointValue;
+        values[armar7de::constants::INDEX] = actualIndexJointValue;
+        values[armar7de::constants::THUMB_FLEXION] = actualThumbJointValue;
+        values[armar7de::constants::THUMB_CIRCUMDUCTION] = actualThumbRotationJointValue;
         return values;
     }
 
-} // namespace devices::ethercat::hand::armar7de
+} // namespace devices::ethercat::hand::armarde
diff --git a/source/devices/ethercat/hand/armar7de/njoint_controller/Shape.h b/source/devices/ethercat/hand/armarde/njoint_controller/Shape.h
similarity index 79%
rename from source/devices/ethercat/hand/armar7de/njoint_controller/Shape.h
rename to source/devices/ethercat/hand/armarde/njoint_controller/Shape.h
index 3c203b97..0db10a3e 100644
--- a/source/devices/ethercat/hand/armar7de/njoint_controller/Shape.h
+++ b/source/devices/ethercat/hand/armarde/njoint_controller/Shape.h
@@ -6,7 +6,6 @@
 #include <devices/ethercat/hand/armar7de/constants.h>
 #include <devices/ethercat/hand/armar7de/joint_controller/AbsolutePosition.h>
 #include <devices/ethercat/hand/armar7de/joint_controller/PWM.h>
-#include <devices/ethercat/hand/armar7de/njoint_controller/Shape.h>
 #include <devices/ethercat/hand/armar7de/njoint_controller/ShapeInterface.h>
 #include <devices/ethercat/hand/armar7de/sub_device/absolute/Config.h>
 #include <devices/ethercat/hand/armar7de/sub_device/absolute/Data.h>
@@ -18,12 +17,12 @@ namespace armarx
     class SensorValue1DoFMotorPWM;
 }
 
-
-namespace devices::ethercat::hand::armar7de
+namespace devices::ethercat::hand::armarde
 {
 
-    using ShapeControllerConfigPtr = IceUtil::Handle<class ShapeControllerConfig>;
+    static constexpr std::string_view controller_name = "NJointArmarDeHandShapeController";
 
+    using ShapeControllerConfigPtr = IceUtil::Handle<class ShapeControllerConfig>;
 
     class ShapeControllerConfig : virtual public armarx::NJointControllerConfig
     {
@@ -40,8 +39,9 @@ namespace devices::ethercat::hand::armar7de
 
     using ShapeControllerPtr = IceInternal::Handle<class ShapeController>;
 
-
-    class ShapeController : public armarx::NJointController, public ShapeControllerInterface
+    class ShapeController :
+        public armarx::NJointController,
+        public armar7de::ShapeControllerInterface
 
     {
 
@@ -57,15 +57,15 @@ namespace devices::ethercat::hand::armar7de
         std::string
         getClassName(const Ice::Current&) const override
         {
-            return constants::NJOINT_CONTROLLER_NAME;
+            return std::string{controller_name};
         }
 
         void stopMotion();
 
-        void setConfigs(const sub_device::relative::DataConfig& fingersConfig,
-                        const sub_device::relative::DataConfig& indexConfig,
-                        const sub_device::relative::DataConfig& thumbConfig,
-                        const sub_device::absolute::DataConfig& thumbRotationConfig);
+        void setConfigs(const armar7de::sub_device::relative::DataConfig& fingersConfig,
+                        const armar7de::sub_device::relative::DataConfig& indexConfig,
+                        const armar7de::sub_device::relative::DataConfig& thumbConfig,
+                        const armar7de::sub_device::absolute::DataConfig& thumbRotationConfig);
 
         std::int16_t getFingersPwm();
         std::int16_t getIndexPwm();
@@ -89,17 +89,17 @@ namespace devices::ethercat::hand::armar7de
 
     private:
         // FIXME forward declaration
-        const sub_device::relative::SensorDataValue* thumbSensorValues;
-        const sub_device::relative::SensorDataValue* fingersSensorValues;
-        const sub_device::relative::SensorDataValue* indexSensorValues;
-        const sub_device::absolute::SensorDataValue* thumbRotationSensorValues;
-
-        PWMControlTarget* thumbFlexionControlTarget;
-        PWMControlTarget* fingersControlTarget;
-        PWMControlTarget* indexControlTarget;
+        const armar7de::sub_device::relative::SensorDataValue* thumbSensorValues;
+        const armar7de::sub_device::relative::SensorDataValue* fingersSensorValues;
+        const armar7de::sub_device::relative::SensorDataValue* indexSensorValues;
+        const armar7de::sub_device::absolute::SensorDataValue* thumbRotationSensorValues;
+
+        armar7de::PWMControlTarget* thumbFlexionControlTarget;
+        armar7de::PWMControlTarget* fingersControlTarget;
+        armar7de::PWMControlTarget* indexControlTarget;
         // PWMControlTarget* thumbRotationControlTarget;
         // FIXME forward declaration
-        AbsolutePositionControlTarget* thumbCircumductionControlTarget;
+        armar7de::AbsolutePositionControlTarget* thumbCircumductionControlTarget;
 
         std::int16_t fingersPwm = 0;
         std::int16_t indexPwm = 0;
@@ -177,4 +177,4 @@ namespace devices::ethercat::hand::armar7de
     protected:
         void rtPreActivateController() override;
     };
-} // namespace devices::ethercat::hand::armar7de
+} // namespace devices::ethercat::hand::armarde
-- 
GitLab