From 6dc09bc45bd2983dd31f583586b732289644757d Mon Sep 17 00:00:00 2001 From: Mansard <nmansard@laas.fr> Date: Thu, 21 Jul 2016 16:43:01 +0200 Subject: [PATCH] [Minor] Remove terminal s in Model::NeutralConfigurations. --- src/multibody/model.hpp | 2 +- src/multibody/model.hxx | 26 ++++++++++++++++++-------- src/parsers/srdf.hpp | 4 ++-- src/python/model.hpp | 4 ++-- unittest/joint-configurations.cpp | 2 +- 5 files changed, 24 insertions(+), 14 deletions(-) diff --git a/src/multibody/model.hpp b/src/multibody/model.hpp index 2f7c56ace..64b413041 100644 --- a/src/multibody/model.hpp +++ b/src/multibody/model.hpp @@ -84,7 +84,7 @@ namespace se3 std::vector<std::string> names; /// \brief Vector of joint's neutral configurations - Eigen::VectorXd neutralConfigurations; + Eigen::VectorXd neutralConfiguration; /// \brief Vector of maximal joint torques Eigen::VectorXd effortLimit; diff --git a/src/multibody/model.hxx b/src/multibody/model.hxx index 56c592259..886bf0642 100644 --- a/src/multibody/model.hxx +++ b/src/multibody/model.hxx @@ -93,11 +93,21 @@ namespace se3 nq += j.nq(); nv += j.nv(); - neutralConfigurations.conservativeResize(nq);neutralConfigurations.bottomRows<D::NQ>() = j.neutralConfiguration(); - effortLimit.conservativeResize(nv);effortLimit.bottomRows<D::NV>().fill(std::numeric_limits<double>::infinity()); - velocityLimit.conservativeResize(nv);velocityLimit.bottomRows<D::NV>().fill(std::numeric_limits<double>::infinity()); - lowerPositionLimit.conservativeResize(nq);lowerPositionLimit.bottomRows<D::NQ>().fill(-std::numeric_limits<double>::infinity()); - upperPositionLimit.conservativeResize(nq);upperPositionLimit.bottomRows<D::NQ>().fill(std::numeric_limits<double>::infinity()); + neutralConfiguration.conservativeResize(nq); + neutralConfiguration.bottomRows<D::NQ>() = j.neutralConfiguration(); + + effortLimit.conservativeResize(nv); + effortLimit.bottomRows<D::NV>().fill(std::numeric_limits<double>::infinity()); + + velocityLimit.conservativeResize(nv); + velocityLimit.bottomRows<D::NV>().fill(std::numeric_limits<double>::infinity()); + + lowerPositionLimit.conservativeResize(nq); + lowerPositionLimit.bottomRows<D::NQ>().fill(-std::numeric_limits<double>::infinity()); + + upperPositionLimit.conservativeResize(nq); + upperPositionLimit.bottomRows<D::NQ>().fill(std::numeric_limits<double>::infinity()); + return idx; } @@ -135,15 +145,15 @@ namespace se3 // Ensure that limits are not inf Eigen::VectorXd neutralConf((lowerPositionLimit.bottomRows<D::NQ>() + upperPositionLimit.bottomRows<D::NQ>())/2 ); - neutralConfigurations.conservativeResize(nq); + neutralConfiguration.conservativeResize(nq); if ( std::isfinite(neutralConf.norm()) ) { - neutralConfigurations.bottomRows<D::NQ>() = neutralConf; + neutralConfiguration.bottomRows<D::NQ>() = neutralConf; } else { assert( false && "One of the position limit is inf or NaN"); - neutralConfigurations.bottomRows<D::NQ>() = j.neutralConfiguration(); + neutralConfiguration.bottomRows<D::NQ>() = j.neutralConfiguration(); } addFrame((jointName!="")?jointName:random(8), idx, SE3::Identity(), JOINT); diff --git a/src/parsers/srdf.hpp b/src/parsers/srdf.hpp index aa82fa354..15b0bd84c 100644 --- a/src/parsers/srdf.hpp +++ b/src/parsers/srdf.hpp @@ -174,8 +174,8 @@ namespace se3 if (joint_id != model.joints.size()) // != model.njoints { - model.neutralConfigurations(joint.idx_q()) = joint_config; // joint with 1 dof - // model.neutralConfigurations.segment(joint.idx_q(),joint.nq()) = joint_config; // joint with more than 1 dof + model.neutralConfiguration(joint.idx_q()) = joint_config; // joint with 1 dof + // model.neutralConfiguration.segment(joint.idx_q(),joint.nq()) = joint_config; // joint with more than 1 dof } else { diff --git a/src/python/model.hpp b/src/python/model.hpp index 7d8b507dc..8d9baaf49 100644 --- a/src/python/model.hpp +++ b/src/python/model.hpp @@ -125,7 +125,7 @@ namespace se3 .add_property("effortLimit", bp::make_function(&ModelPythonVisitor::effortLimit), "Joint max effort") - .add_property("neutralConfigurations", bp::make_function(&ModelPythonVisitor::neutralConfigurations), "Joint's neutral configurations") + .add_property("neutralConfiguration", bp::make_function(&ModelPythonVisitor::neutralConfiguration), "Joint's neutral configurations") .add_property("velocityLimit", bp::make_function(&ModelPythonVisitor::velocityLimit), "Joint max velocity") .add_property("lowerPositionLimit", bp::make_function(&ModelPythonVisitor::lowerPositionLimit), "Limit for joint lower position") .add_property("upperPositionLimit", bp::make_function(&ModelPythonVisitor::upperPositionLimit), "Limit for joint upper position") @@ -172,7 +172,7 @@ namespace se3 } - static Eigen::VectorXd neutralConfigurations(ModelHandler & m) {return m->neutralConfigurations;} + static Eigen::VectorXd neutralConfiguration(ModelHandler & m) {return m->neutralConfiguration;} static Eigen::VectorXd effortLimit(ModelHandler & m) {return m->effortLimit;} static Eigen::VectorXd velocityLimit(ModelHandler & m) {return m->velocityLimit;} static Eigen::VectorXd lowerPositionLimit(ModelHandler & m) {return m->lowerPositionLimit;} diff --git a/unittest/joint-configurations.cpp b/unittest/joint-configurations.cpp index d7941f51f..8d9b268c6 100644 --- a/unittest/joint-configurations.cpp +++ b/unittest/joint-configurations.cpp @@ -483,7 +483,7 @@ BOOST_AUTO_TEST_CASE ( neutral_configuration_test ) 0,0,0; - BOOST_CHECK_MESSAGE(model.neutralConfigurations.isApprox(expected, 1e-12), "neutral configurations - wrong results"); + BOOST_CHECK_MESSAGE(model.neutralConfiguration.isApprox(expected, 1e-12), "neutral configuration - wrong results"); } BOOST_AUTO_TEST_CASE ( uniform_sampling_test ) -- GitLab