diff --git a/CHANGELOG.md b/CHANGELOG.md
index 161888f2..f650e2c0 100644
--- a/CHANGELOG.md
+++ b/CHANGELOG.md
@@ -7,8 +7,14 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
## [Unreleased]
+### urdf
+- Fix location of `l/r_sole` frames(https://github.com/icub-tech-iit/ergocub-software/issues/186)
+
## [0.5.0] - 2023-10-26
+### urdf
+- Fixed wobbling of the models after moving feet link frames
+
## [0.4.0] - 2023-09-04
### urdf
diff --git a/tests/ergocub-model-test.cpp b/tests/ergocub-model-test.cpp
index baa5e97a..15ad30fe 100644
--- a/tests/ergocub-model-test.cpp
+++ b/tests/ergocub-model-test.cpp
@@ -163,7 +163,7 @@ bool checkBaseLink(iDynTree::KinDynComputations & comp)
return true;
}
-bool checkSolesAreParallel(iDynTree::KinDynComputations & comp)
+bool checkSolesAreParallelAndCorrectlyPlaced(iDynTree::KinDynComputations & comp)
{
iDynTree::LinkIndex rootLinkIdx = comp.getFrameIndex("root_link");
@@ -192,6 +192,32 @@ bool checkSolesAreParallel(iDynTree::KinDynComputations & comp)
iDynTree::Transform root_H_l_sole = comp.getRelativeTransform(rootLinkIdx,l_sole);
iDynTree::Transform root_H_r_sole = comp.getRelativeTransform(rootLinkIdx,r_sole);
+ iDynTree::Transform root_H_l_sole_expected(iDynTree::Rotation(1, 0, 0,
+ 0, 1, 0,
+ 0, 0, 1),
+ iDynTree::Position(0.04403,0.0744,-0.7793));
+ iDynTree::Transform root_H_r_sole_expected(iDynTree::Rotation(1, 0, 0,
+ 0, 1, 0,
+ 0, 0, 1),
+ iDynTree::Position(0.04403,-0.0744,-0.7793));
+
+
+ if (!checkTransformAreEqual(root_H_l_sole, root_H_l_sole_expected, 1e-5))
+ {
+ std::cerr << "ergocub-model-test : transform between root_H_l_sole is not the expected one, test failed." << std::endl;
+ std::cerr << "ergocub-model-test : root_H_l_sole :" << root_H_l_sole.toString() << std::endl;
+ std::cerr << "ergocub-model-test : root_H_l_sole_expected :" << root_H_l_sole_expected.toString() << std::endl;
+ return false;
+ }
+
+ if (!checkTransformAreEqual(root_H_r_sole, root_H_r_sole_expected, 1e-5))
+ {
+ std::cerr << "ergocub-model-test : transform between root_H_r_sole is not the expected one, test failed." << std::endl;
+ std::cerr << "ergocub-model-test : root_H_r_sole :" << root_H_r_sole.toString() << std::endl;
+ std::cerr << "ergocub-model-test : root_H_r_sole_expected :" << root_H_r_sole_expected.toString() << std::endl;
+ return false;
+ }
+
// height of the sole should be equal
double l_sole_height = root_H_l_sole.getPosition().getVal(2);
double r_sole_height = root_H_r_sole.getPosition().getVal(2);
@@ -446,21 +472,21 @@ bool checkFTSensorsAreEvenAndNotNull(iDynTree::ModelLoader & mdlLoader)
}
-bool checkFTSensorIsCorrectlyOriented(iDynTree::KinDynComputations & comp,
+bool checkFrameIsCorrectlyOriented(iDynTree::KinDynComputations & comp,
const iDynTree::Rotation& expected,
- const std::string& sensorName)
+ const std::string& frameName)
{
// Depending on the ergocub model, the sensor could be absent
- if (!comp.model().isFrameNameUsed(sensorName))
+ if (!comp.model().isFrameNameUsed(frameName))
{
return true;
}
- iDynTree::Rotation actual = comp.getRelativeTransform("root_link", sensorName).getRotation();
+ iDynTree::Rotation actual = comp.getRelativeTransform("root_link", frameName).getRotation();
if (!checkMatrixAreEqual(expected, actual, 1e-3))
{
- std::cerr << "ergocub-model-test : transform between root_link and " << sensorName << " is not the expected one, test failed." << std::endl;
+ std::cerr << "ergocub-model-test : transform between root_link and " << frameName << " is not the expected one, test failed." << std::endl;
std::cerr << "ergocub-model-test : Expected transform : " << expected.toString() << std::endl;
std::cerr << "ergocub-model-test : Actual transform : " << actual.toString() << std::endl;
return false;
@@ -470,6 +496,7 @@ bool checkFTSensorIsCorrectlyOriented(iDynTree::KinDynComputations & comp,
}
+
bool checkFTSensorsAreCorrectlyOriented(iDynTree::KinDynComputations & comp)
{
@@ -497,14 +524,14 @@ bool checkFTSensorsAreCorrectlyOriented(iDynTree::KinDynComputations & comp)
0.5, 0.866025, 0,
0, 0, -1);
- bool ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameLeftArmExpected, "l_arm_ft");
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameRightArmExpected, "r_arm_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_L_sensorFrameExpectedLeg, "l_leg_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedLeg, "r_leg_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "l_foot_rear_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "r_foot_rear_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "l_foot_front_ft") && ok;
- ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "r_foot_front_ft") && ok;
+ bool ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameLeftArmExpected, "l_arm_ft");
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameRightArmExpected, "r_arm_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_L_sensorFrameExpectedLeg, "l_leg_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedLeg, "r_leg_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "l_foot_rear_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "r_foot_rear_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "l_foot_front_ft") && ok;
+ ok = checkFrameIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpectedFoot, "r_foot_front_ft") && ok;
return ok;
}
@@ -726,7 +753,7 @@ int main(int argc, char ** argv)
// Check if l_sole/r_sole have the same distance from the root_link
- if( !checkSolesAreParallel(comp) )
+ if( !checkSolesAreParallelAndCorrectlyPlaced(comp) )
{
return EXIT_FAILURE;
}
diff --git a/urdf/ergoCub/robots/ergoCubGazeboV1/model.urdf b/urdf/ergoCub/robots/ergoCubGazeboV1/model.urdf
index 8c9325a4..97d64ff8 100644
--- a/urdf/ergoCub/robots/ergoCubGazeboV1/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubGazeboV1/model.urdf
@@ -280,7 +280,7 @@
-
+
@@ -600,7 +600,7 @@
-
+
diff --git a/urdf/ergoCub/robots/ergoCubGazeboV1_1/model.urdf b/urdf/ergoCub/robots/ergoCubGazeboV1_1/model.urdf
index 3430d585..78d33724 100644
--- a/urdf/ergoCub/robots/ergoCubGazeboV1_1/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubGazeboV1_1/model.urdf
@@ -1241,8 +1241,8 @@
-
-
+
+
@@ -1251,7 +1251,7 @@
-
+
@@ -1571,8 +1571,8 @@
-
-
+
+
@@ -1604,8 +1604,8 @@
-
-
+
+
@@ -1614,7 +1614,7 @@
-
+
@@ -2508,7 +2508,7 @@
-
+
@@ -2874,7 +2874,7 @@
-
+
diff --git a/urdf/ergoCub/robots/ergoCubGazeboV1_1_minContacts/model.urdf b/urdf/ergoCub/robots/ergoCubGazeboV1_1_minContacts/model.urdf
index 9c22d5ae..6a2cae1b 100644
--- a/urdf/ergoCub/robots/ergoCubGazeboV1_1_minContacts/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubGazeboV1_1_minContacts/model.urdf
@@ -1133,8 +1133,8 @@
-
-
+
+
@@ -1143,7 +1143,7 @@
-
+
@@ -1433,8 +1433,8 @@
-
-
+
+
@@ -1463,8 +1463,8 @@
-
-
+
+
@@ -1473,7 +1473,7 @@
-
+
@@ -2328,7 +2328,7 @@
-
+
@@ -2694,7 +2694,7 @@
-
+
diff --git a/urdf/ergoCub/robots/ergoCubGazeboV1_minContacts/model.urdf b/urdf/ergoCub/robots/ergoCubGazeboV1_minContacts/model.urdf
index b9c9e20d..207ebe08 100644
--- a/urdf/ergoCub/robots/ergoCubGazeboV1_minContacts/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubGazeboV1_minContacts/model.urdf
@@ -280,7 +280,7 @@
-
+
@@ -600,7 +600,7 @@
-
+
diff --git a/urdf/ergoCub/robots/ergoCubSN000/model.urdf b/urdf/ergoCub/robots/ergoCubSN000/model.urdf
index 87413a34..995ec051 100644
--- a/urdf/ergoCub/robots/ergoCubSN000/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubSN000/model.urdf
@@ -280,7 +280,7 @@
-
+
@@ -600,7 +600,7 @@
-
+
diff --git a/urdf/ergoCub/robots/ergoCubSN001/model.urdf b/urdf/ergoCub/robots/ergoCubSN001/model.urdf
index c165fec4..e8e07897 100644
--- a/urdf/ergoCub/robots/ergoCubSN001/model.urdf
+++ b/urdf/ergoCub/robots/ergoCubSN001/model.urdf
@@ -1241,8 +1241,8 @@
-
-
+
+
@@ -1251,8 +1251,8 @@
-
-
+
+
@@ -1571,8 +1571,8 @@
-
-
+
+
@@ -1604,8 +1604,8 @@
-
-
+
+
@@ -1614,8 +1614,8 @@
-
-
+
+
@@ -2508,7 +2508,7 @@
-
+
@@ -2874,7 +2874,7 @@
-
+