From 0042976e86a7b405297d4ad6a335b6c064b19bb4 Mon Sep 17 00:00:00 2001 From: Joseph Mirabel <jmirabel@laas.fr> Date: Tue, 2 Aug 2016 11:48:50 +0200 Subject: [PATCH] [C++] Update unit tests --- unittest/compute-all-terms.cpp | 8 ++++---- unittest/finite-differences.cpp | 2 +- unittest/frames.cpp | 4 ++-- unittest/geom.cpp | 10 +++++----- unittest/jacobian.cpp | 8 ++++---- unittest/joint-configurations.cpp | 6 +++--- 6 files changed, 19 insertions(+), 19 deletions(-) diff --git a/unittest/compute-all-terms.cpp b/unittest/compute-all-terms.cpp index ab96ecb54..368db7155 100644 --- a/unittest/compute-all-terms.cpp +++ b/unittest/compute-all-terms.cpp @@ -73,7 +73,7 @@ BOOST_AUTO_TEST_CASE ( test_against_algo ) BOOST_CHECK (data.J.isApprox(data_other.J, 1e-12)); BOOST_CHECK (data.Jcom.isApprox(data_other.Jcom, 1e-12)); - for (int k=0; k<model.nbody; ++k) + for (int k=0; k<model.njoint; ++k) { BOOST_CHECK (data.com[(size_t)k].isApprox(data_other.com[(size_t)k], 1e-12)); BOOST_CHECK (data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k], 1e-12)); @@ -103,7 +103,7 @@ BOOST_AUTO_TEST_CASE ( test_against_algo ) BOOST_CHECK (data.J.isApprox(data_other.J, 1e-12)); BOOST_CHECK (data.Jcom.isApprox(data_other.Jcom, 1e-12)); - for (int k=0; k<model.nbody; ++k) + for (int k=0; k<model.njoint; ++k) { BOOST_CHECK (data.com[(size_t)k].isApprox(data_other.com[(size_t)k], 1e-12)); BOOST_CHECK (data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k], 1e-12)); @@ -134,7 +134,7 @@ BOOST_AUTO_TEST_CASE ( test_against_algo ) BOOST_CHECK (data.J.isApprox(data_other.J, 1e-12)); BOOST_CHECK (data.Jcom.isApprox(data_other.Jcom, 1e-12)); - for (int k=0; k<model.nbody; ++k) + for (int k=0; k<model.njoint; ++k) { BOOST_CHECK (data.com[(size_t)k].isApprox(data_other.com[(size_t)k], 1e-12)); BOOST_CHECK (data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k], 1e-12)); @@ -165,7 +165,7 @@ BOOST_AUTO_TEST_CASE ( test_against_algo ) BOOST_CHECK (data.J.isApprox(data_other.J, 1e-12)); BOOST_CHECK (data.Jcom.isApprox(data_other.Jcom, 1e-12)); - for (int k=0; k<model.nbody; ++k) + for (int k=0; k<model.njoint; ++k) { BOOST_CHECK (data.com[(size_t)k].isApprox(data_other.com[(size_t)k], 1e-12)); BOOST_CHECK (data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k], 1e-12)); diff --git a/unittest/finite-differences.cpp b/unittest/finite-differences.cpp index cf87062eb..c361be568 100644 --- a/unittest/finite-differences.cpp +++ b/unittest/finite-differences.cpp @@ -160,7 +160,7 @@ BOOST_AUTO_TEST_CASE (test_jacobian_vs_finit_diff) q.segment<4>(3).normalize(); computeJacobians(model,data,q); - Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.nbody-1); + Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.njoint-1); Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0); getJacobian<false>(model,data,idx,Jrh); diff --git a/unittest/frames.cpp b/unittest/frames.cpp index ff32af394..1b305cf0d 100644 --- a/unittest/frames.cpp +++ b/unittest/frames.cpp @@ -39,7 +39,7 @@ BOOST_AUTO_TEST_CASE ( test_kinematics ) se3::Model model; se3::buildModels::humanoidSimple(model); - Model::Index parent_idx = model.existJointName("rarm2_joint")?model.getJointId("rarm2_joint"):(Model::Index)(model.nbody-1); + Model::Index parent_idx = model.existJointName("rarm2_joint")?model.getJointId("rarm2_joint"):(Model::Index)(model.njoint-1); const std::string & frame_name = std::string( model.getJointName(parent_idx)+ "_frame"); const SE3 & framePlacement = SE3::Random(); model.addFrame(frame_name, parent_idx, framePlacement); @@ -61,7 +61,7 @@ BOOST_AUTO_TEST_CASE ( test_jacobian ) Model model; buildModels::humanoidSimple(model); - Model::Index parent_idx = model.existJointName("rarm2_joint")?model.getJointId("rarm2_joint"):(Model::Index)(model.nbody-1); + Model::Index parent_idx = model.existJointName("rarm2_joint")?model.getJointId("rarm2_joint"):(Model::Index)(model.njoint-1); const std::string & frame_name = std::string( model.getJointName(parent_idx)+ "_frame"); const SE3 & framePlacement = SE3::Random(); model.addFrame(frame_name, parent_idx, framePlacement); diff --git a/unittest/geom.cpp b/unittest/geom.cpp index 71e827b1d..dc9b53ed5 100644 --- a/unittest/geom.cpp +++ b/unittest/geom.cpp @@ -47,7 +47,7 @@ typedef std::map <std::string, se3::SE3> PositionsMap_t; typedef std::map <std::string, se3::SE3> JointPositionsMap_t; typedef std::map <std::string, se3::SE3> GeometryPositionsMap_t; typedef std::map <std::pair < std::string , std::string >, fcl::DistanceResult > PairDistanceMap_t; -JointPositionsMap_t fillPinocchioJointPositions(const se3::Data & data); +JointPositionsMap_t fillPinocchioJointPositions(const se3::Model& model, const se3::Data & data); GeometryPositionsMap_t fillPinocchioGeometryPositions(const se3::GeometryData & data_geom); #ifdef WITH_HPP_MODEL_URDF JointPositionsMap_t fillHppJointPositions(const hpp::model::HumanoidRobotPtr_t robot); @@ -346,7 +346,7 @@ BOOST_AUTO_TEST_CASE ( romeo_joints_meshes_positions ) /// ********** COMPARISON ********* /// /// ********************************* /// // retrieve all joint and geometry objects positions - JointPositionsMap_t joints_pin = fillPinocchioJointPositions(data); + JointPositionsMap_t joints_pin = fillPinocchioJointPositions(model, data); JointPositionsMap_t joints_hpp = fillHppJointPositions(humanoidRobot); GeometryPositionsMap_t geom_pin = fillPinocchioGeometryPositions(data_geom); GeometryPositionsMap_t geom_hpp = fillHppGeometryPositions(humanoidRobot); @@ -489,12 +489,12 @@ BOOST_AUTO_TEST_CASE ( hrp2_mesh_distance) #endif BOOST_AUTO_TEST_SUITE_END () -JointPositionsMap_t fillPinocchioJointPositions(const se3::Data & data) +JointPositionsMap_t fillPinocchioJointPositions(const se3::Model& model, const se3::Data & data) { JointPositionsMap_t result; - for (se3::Model::Index i = 0; i < (se3::Model::Index)data.model.nbody; ++i) + for (se3::Model::Index i = 0; i < (se3::Model::Index)model.njoint; ++i) { - result[data.model.getJointName(i)] = data.oMi[i]; + result[model.getJointName(i)] = data.oMi[i]; } return result; } diff --git a/unittest/jacobian.cpp b/unittest/jacobian.cpp index ff3c9dfd2..9c6e4b855 100644 --- a/unittest/jacobian.cpp +++ b/unittest/jacobian.cpp @@ -43,7 +43,7 @@ BOOST_AUTO_TEST_CASE ( test_jacobian ) VectorXd q = VectorXd::Zero(model.nq); computeJacobians(model,data,q); - Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.nbody-1); + Model::Index idx = model.existJointName("rarm2")?model.getJointId("rarm2"):(Model::Index)(model.njoint-1); Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0); getJacobian<false>(model,data,idx,Jrh); @@ -110,7 +110,7 @@ BOOST_AUTO_TEST_CASE ( test_timings ) if( flag >> 1 & 1 ) { computeJacobians(model,data,q); - Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.nbody-1); + Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoint-1); Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0); timer.tic(); @@ -125,7 +125,7 @@ BOOST_AUTO_TEST_CASE ( test_timings ) if( flag >> 2 & 1 ) { computeJacobians(model,data,q); - Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.nbody-1); + Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoint-1); Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0); timer.tic(); @@ -140,7 +140,7 @@ BOOST_AUTO_TEST_CASE ( test_timings ) if( flag >> 3 & 1 ) { computeJacobians(model,data,q); - Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.nbody-1); + Model::Index idx = model.existJointName("rarm6")?model.getJointId("rarm6"):(Model::Index)(model.njoint-1); Data::Matrix6x Jrh(6,model.nv); Jrh.fill(0); timer.tic(); diff --git a/unittest/joint-configurations.cpp b/unittest/joint-configurations.cpp index c33831f8c..e4308c52d 100644 --- a/unittest/joint-configurations.cpp +++ b/unittest/joint-configurations.cpp @@ -369,7 +369,7 @@ BOOST_AUTO_TEST_CASE ( distance_computation_test ) Eigen::Quaterniond quat_ff_2(q2[6],q2[3],q2[4],q2[5]); Eigen::Quaterniond quat_spherical_2(q2[10],q2[7],q2[8],q2[9]); - Eigen::VectorXd expected(model.nbody-1); + Eigen::VectorXd expected(model.njoint-1); // Quaternion freeflyer // Compute rotation vector between q2 and q1. @@ -408,14 +408,14 @@ BOOST_AUTO_TEST_CASE ( distance_computation_test ) // Test Case 1 : Distance between two zero configs // Eigen::VectorXd q_zero(Eigen::VectorXd::Zero(model.nq)); - expected = Eigen::VectorXd::Zero(model.nbody-1); + expected = Eigen::VectorXd::Zero(model.njoint-1); result = distance(model,q_zero,q_zero); BOOST_CHECK_MESSAGE(result.isApprox(expected, 1e-12), "Distance between two zero configs of full model - wrong results"); // // Test Case 2 : Distance between two same configs // - expected = Eigen::VectorXd::Zero(model.nbody-1); + expected = Eigen::VectorXd::Zero(model.njoint-1); result = distance(model,q1,q1); BOOST_CHECK_MESSAGE(result.isApprox(expected, 1e-12), "Distance between two same configs of full model - wrong results"); -- GitLab