From b126270ecbfcda62e530518f8c08691ae602fe19 Mon Sep 17 00:00:00 2001 From: jcarpent <jcarpent@laas.fr> Date: Fri, 29 Jul 2016 13:28:42 +0200 Subject: [PATCH] [Unit test] Update buildModel call with new API --- unittest/geom.cpp | 12 ++++++++---- unittest/value.cpp | 28 +++++++++++++++------------- 2 files changed, 23 insertions(+), 17 deletions(-) diff --git a/unittest/geom.cpp b/unittest/geom.cpp index 059432e40..71e827b1d 100644 --- a/unittest/geom.cpp +++ b/unittest/geom.cpp @@ -202,7 +202,8 @@ BOOST_AUTO_TEST_CASE ( loading_model ) std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/"; package_dirs.push_back(meshDir); - Model model = se3::urdf::buildModel(filename, se3::JointModelFreeFlyer()); + Model model; + se3::urdf::buildModel(filename, se3::JointModelFreeFlyer(),model); GeometryModel geometry_model = se3::urdf::buildGeom(model, filename, package_dirs, se3::COLLISION); Data data(model); @@ -227,7 +228,8 @@ BOOST_AUTO_TEST_CASE (radius) std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/"; package_dirs.push_back(meshDir); - se3::Model model = se3::urdf::buildModel(filename, se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename, se3::JointModelFreeFlyer(),model); se3::GeometryModel geom = se3::urdf::buildGeom(model, filename, package_dirs, se3::COLLISION); Data data(model); GeometryData geomData(geom); @@ -299,7 +301,8 @@ BOOST_AUTO_TEST_CASE ( romeo_joints_meshes_positions ) std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/"; package_dirs.push_back(meshDir); - se3::Model model = se3::urdf::buildModel(filename, se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename, se3::JointModelFreeFlyer(),model); se3::GeometryModel geom = se3::urdf::buildGeom(model, filename, package_dirs, se3::COLLISION); std::cout << model << std::endl; @@ -406,7 +409,8 @@ BOOST_AUTO_TEST_CASE ( hrp2_mesh_distance) std::string meshDir = PINOCCHIO_SOURCE_DIR"/models/"; package_dirs.push_back(meshDir); - se3::Model model = se3::urdf::buildModel(filename, se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename, se3::JointModelFreeFlyer(),model); se3::GeometryModel geom = se3::urdf::buildGeom(model, filename, package_dirs, se3::COLLISION); std::cout << model << std::endl; diff --git a/unittest/value.cpp b/unittest/value.cpp index d0d9ed2da..4ac8022ff 100644 --- a/unittest/value.cpp +++ b/unittest/value.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015 CNRS +// Copyright (c) 2015-2016 CNRS // // This file is part of Pinocchio // Pinocchio is free software: you can redistribute it @@ -32,7 +32,7 @@ #include <iomanip> #include "pinocchio/multibody/model.hpp" - #include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/parsers/urdf.hpp" #include "pinocchio/algorithm/rnea.hpp" #include "pinocchio/algorithm/kinematics.hpp" @@ -47,7 +47,8 @@ BOOST_AUTO_TEST_CASE ( test_000 ) { std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf"; - se3::Model model = se3::urdf::buildModel(filename,se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename,se3::JointModelFreeFlyer(),model); model.gravity.linear( Eigen::Vector3d(0,0,-9.8)); se3::Data data(model); @@ -72,7 +73,8 @@ BOOST_AUTO_TEST_CASE( test_0V0 ) { std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf"; - se3::Model model = se3::urdf::buildModel(filename,se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename,se3::JointModelFreeFlyer(),model); model.gravity.linear( Eigen::Vector3d(0,0,-9.8)); se3::Data data(model); @@ -97,7 +99,8 @@ BOOST_AUTO_TEST_CASE( test_0VA ) { std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf"; - se3::Model model = se3::urdf::buildModel(filename,se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename,se3::JointModelFreeFlyer(),model); model.gravity.linear( Eigen::Vector3d(0,0,-9.8)); se3::Data data(model); @@ -120,7 +123,8 @@ BOOST_AUTO_TEST_CASE( test_Q00 ) { std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf"; - se3::Model model = se3::urdf::buildModel(filename,se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename,se3::JointModelFreeFlyer(),model); model.gravity.linear( Eigen::Vector3d(0,0,-9.8)); se3::Data data(model); @@ -137,8 +141,8 @@ BOOST_AUTO_TEST_CASE( test_Q00 ) v = Eigen::VectorXd::Zero(model.nv); a = Eigen::VectorXd::Zero(model.nv); rnea(model,data,q,v,a); - std::cout << expected << "\n ---------------- \n" - << data.tau << std::endl; +// std::cout << expected << "\n ---------------- \n" +// << data.tau << std::endl; BOOST_CHECK (expected.isApprox(data.tau,1e-6)); @@ -148,7 +152,8 @@ BOOST_AUTO_TEST_CASE( test_QVA ) { std::string filename = PINOCCHIO_SOURCE_DIR"/models/simple_humanoid.urdf"; - se3::Model model = se3::urdf::buildModel(filename,se3::JointModelFreeFlyer()); + se3::Model model; + se3::urdf::buildModel(filename,se3::JointModelFreeFlyer(),model); model.gravity.linear( Eigen::Vector3d(0,0,-9.8)); se3::Data data(model); @@ -166,8 +171,5 @@ BOOST_AUTO_TEST_CASE( test_QVA ) rnea(model,data,q,v,a); BOOST_CHECK (expected.isApprox(data.tau,1e-7)); } + BOOST_AUTO_TEST_SUITE_END () - - - - -- GitLab