Skip to content

Commit

Permalink
Merge pull request #97 from robotology/test/92
Browse files Browse the repository at this point in the history
Add test to check that the FT sensors are correctly oriented
  • Loading branch information
fiorisi authored Jun 21, 2018
2 parents e18d734 + 894ed72 commit 7a77e78
Showing 1 changed file with 54 additions and 1 deletion.
55 changes: 54 additions & 1 deletion tests/icub-model-test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,54 @@ bool checkFTSensorsAreEvenAndNotNull(iDynTree::ModelLoader & mdlLoader)
return true;
}

bool checkFTSensorIsCorrectlyOriented(iDynTree::KinDynComputations & comp,
const iDynTree::Rotation& expected,
const std::string& sensorName)
{
// Depending on the icub model, the sensor could be absent
if (!comp.model().isFrameNameUsed(sensorName))
{
return true;
}

iDynTree::Rotation actual = comp.getRelativeTransform("root_link", sensorName).getRotation();

if (!checkMatrixAreEqual(expected, actual, 1e-3))
{
std::cerr << "icub-model-test : transform between root_link and " << sensorName << " is not the expected one, test failed." << std::endl;
std::cerr << "icub-model-test : Expected transform : " << expected.toString() << std::endl;
std::cerr << "icub-model-test : Actual transform : " << actual.toString() << std::endl;
return false;
}

return true;
}


/**
* Check that the F/T sensor have the correct orientation.
*
* See https://github.com/robotology/icub-model-generator/issues/92
*/
bool checkFTSensorsAreCorrectlyOriented(iDynTree::KinDynComputations & comp)
{
// The rotation of all the F/T sensors in the iCub robot when in zero position are the same
iDynTree::Rotation rootLink_R_sensorFrameExpected =
iDynTree::Rotation(-1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, -1.0);


bool ok = checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "l_arm_ft_sensor");
ok = ok && checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "r_arm_ft_sensor");
ok = ok && checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "l_leg_ft_sensor");
ok = ok && checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "r_leg_ft_sensor");
ok = ok && checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "l_foot_ft_sensor");
ok = ok && checkFTSensorIsCorrectlyOriented(comp, rootLink_R_sensorFrameExpected, "r_foot_ft_sensor");

return ok;
}

int main(int argc, char ** argv)
{
yarp::os::Property prop;
Expand Down Expand Up @@ -343,12 +391,17 @@ int main(int argc, char ** argv)
iDynTree::ModelLoader mdlLoader;
mdlLoader.loadModelFromFile(modelPath);


if( !checkFTSensorsAreEvenAndNotNull(mdlLoader) )
{
return EXIT_FAILURE;
}

if (!checkFTSensorsAreCorrectlyOriented(comp))
{
return EXIT_FAILURE;
}


std::cerr << "Check for model " << modelPath << " concluded correctly!" << std::endl;

return EXIT_SUCCESS;
Expand Down

0 comments on commit 7a77e78

Please sign in to comment.