From 2f8c3d3e0eddcb8deaae5da449c1a0927ca21158 Mon Sep 17 00:00:00 2001 From: Justin Carpentier <justin.carpentier@inria.fr> Date: Mon, 30 Mar 2020 16:22:16 +0200 Subject: [PATCH] srdf: allows removing of collision pairs when FCL is not present --- src/parsers/srdf.hpp | 5 ----- src/parsers/srdf.hxx | 24 ++++++++++-------------- 2 files changed, 10 insertions(+), 19 deletions(-) diff --git a/src/parsers/srdf.hpp b/src/parsers/srdf.hpp index f83d69bd7..67e620006 100644 --- a/src/parsers/srdf.hpp +++ b/src/parsers/srdf.hpp @@ -13,8 +13,6 @@ namespace pinocchio namespace srdf { -#ifdef PINOCCHIO_WITH_HPP_FCL - /// /// \brief Deactive all possible collision pairs mentioned in the SRDF file. /// It throws if the SRDF file is incorrect. @@ -44,8 +42,6 @@ namespace pinocchio const std::string & xmlString, const bool verbose = false); -#endif // ifdef PINOCCHIO_WITH_HPP_FCL - /// /// \brief Get the reference configurations of a given model associated to a SRDF file. /// It throws if the SRDF file is incorrect. The reference configurations are @@ -76,7 +72,6 @@ namespace pinocchio std::istream & xmlStream, const bool verbose = false); - /// /// \brief Load the rotor params of a given model associated to a SRDF file. /// It throws if the SRDF file is incorrect. diff --git a/src/parsers/srdf.hxx b/src/parsers/srdf.hxx index 552cbf975..4b6210dbb 100644 --- a/src/parsers/srdf.hxx +++ b/src/parsers/srdf.hxx @@ -23,8 +23,6 @@ namespace pinocchio { namespace srdf { - -#ifdef PINOCCHIO_WITH_HPP_FCL namespace details { template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> @@ -129,8 +127,6 @@ namespace pinocchio details::removeCollisionPairs(model, geom_model, srdf_stream, verbose); } -#endif // ifdef PINOCCHIO_WITH_HPP_FCL - template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model, const std::string & filename, @@ -210,8 +206,8 @@ namespace pinocchio typedef typename Model::ConfigVectorType ConfigVectorType; typedef boost::fusion::vector<const std::string&, - const ConfigVectorType&, - ConfigVectorType&> ArgsType; + const ConfigVectorType&, + ConfigVectorType&> ArgsType; template<typename JointModel> static void algo(const JointModelBase<JointModel> & joint, @@ -225,9 +221,9 @@ namespace pinocchio private: template<int axis> static void _algo (const JointModelRevoluteUnboundedTpl<Scalar,Options,axis> & joint, - const std::string& joint_name, - const ConfigVectorType& fromXML, - ConfigVectorType& config) + const std::string& joint_name, + const ConfigVectorType& fromXML, + ConfigVectorType& config) { typedef JointModelRevoluteUnboundedTpl<Scalar,Options,axis> JointModelRUB; PINOCCHIO_STATIC_ASSERT(JointModelRUB::NQ == 2, JOINT_MODEL_REVOLUTE_SHOULD_HAVE_2_PARAMETERS); @@ -235,16 +231,16 @@ namespace pinocchio std::cerr << "Could not read joint config (" << joint_name << " , " << fromXML.transpose() << ")" << std::endl; else { SINCOS(fromXML[0], - &config[joint.idx_q()+1], - &config[joint.idx_q()+0]); + &config[joint.idx_q()+1], + &config[joint.idx_q()+0]); } } template<typename JointModel> static void _algo (const JointModel & joint, - const std::string& joint_name, - const ConfigVectorType& fromXML, - ConfigVectorType& config) + const std::string& joint_name, + const ConfigVectorType& fromXML, + ConfigVectorType& config) { if (joint.nq() != fromXML.size()) std::cerr << "Could not read joint config (" << joint_name << " , " << fromXML.transpose() << ")" << std::endl; -- GitLab