diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp index 9d1daf289d45ae9df45e9a817b3e0a40d5a268ac..182be33eff5c3668e8e389e30040b339440dcb14 100644 --- a/VirtualRobot/IK/DifferentialIK.cpp +++ b/VirtualRobot/IK/DifferentialIK.cpp @@ -21,8 +21,8 @@ using namespace Eigen; namespace VirtualRobot { -DifferentialIK::DifferentialIK(RobotNodeSetPtr _rns, RobotNodePtr _coordSystem, JacobiProvider::InverseJacobiMethod invJacMethod) : - JacobiProvider(_rns,invJacMethod), coordSystem(_coordSystem), nRows(0) +DifferentialIK::DifferentialIK(RobotNodeSetPtr _rns, RobotNodePtr _coordSystem, JacobiProvider::InverseJacobiMethod invJacMethod, float invParam) : + JacobiProvider(_rns,invJacMethod), coordSystem(_coordSystem), invParam(invParam), nRows(0) { if (!rns) THROW_VR_EXCEPTION("Null data"); @@ -357,7 +357,7 @@ Eigen::MatrixXf DifferentialIK::getPseudoInverseJacobianMatrix(SceneObjectPtr tc #ifdef CHECK_PERFORMANCE clock_t startT2 = clock(); #endif - Eigen::MatrixXf res = computePseudoInverseJacobianMatrix(Jacobian); + Eigen::MatrixXf res = computePseudoInverseJacobianMatrix(Jacobian,invParam); #ifdef CHECK_PERFORMANCE clock_t endT = clock(); float diffClock1 = (float)(((float)(startT2 - startT) / (float)CLOCKS_PER_SEC) * 1000.0f); diff --git a/VirtualRobot/IK/DifferentialIK.h b/VirtualRobot/IK/DifferentialIK.h index b02d5abdc5ab5ca679833f3fb5d972c0cd6bb8df..c4713b6fc8816f9f831ab7da5946e5c06ec25402 100644 --- a/VirtualRobot/IK/DifferentialIK.h +++ b/VirtualRobot/IK/DifferentialIK.h @@ -113,8 +113,10 @@ public: @brief Initialize a Jacobian object. \param rns The robotNodes (i.e., joints) for which the Jacobians should be calculated. \param coordSystem The coordinate system in which the Jacobians are defined. By default the global coordinate system is used. + \param invJacMethod The method for inverting the Jacobian + \param invParam Only used when != 0.0f */ - DifferentialIK(RobotNodeSetPtr rns, RobotNodePtr coordSystem = RobotNodePtr(), JacobiProvider::InverseJacobiMethod invJacMethod = eSVD); + DifferentialIK(RobotNodeSetPtr rns, RobotNodePtr coordSystem = RobotNodePtr(), JacobiProvider::InverseJacobiMethod invJacMethod = eSVD, float invParam = 0.0f); /*! @brief Sets the target position for (one of) the tcp(s). \param goal Target pose of the tcp. @@ -263,6 +265,7 @@ public: virtual void setMaxPositionStep(float s); protected: + float invParam; void setNRows(); bool checkTolerances(); std::vector<SceneObjectPtr> tcp_set; diff --git a/VirtualRobot/IK/JacobiProvider.cpp b/VirtualRobot/IK/JacobiProvider.cpp index 79e39a2ff3321af744cabeda405f7ee5ab48b6c7..f3b95043513c9c2becf5be32e2db5ede4b88c4b6 100644 --- a/VirtualRobot/IK/JacobiProvider.cpp +++ b/VirtualRobot/IK/JacobiProvider.cpp @@ -50,6 +50,11 @@ Eigen::MatrixXf JacobiProvider::getPseudoInverseJacobianMatrix() } Eigen::MatrixXf JacobiProvider::computePseudoInverseJacobianMatrix(const Eigen::MatrixXf &m) const +{ + return computePseudoInverseJacobianMatrix(m,0.0f); +} + +Eigen::MatrixXf JacobiProvider::computePseudoInverseJacobianMatrix(const Eigen::MatrixXf &m, float invParameter) const { #ifdef CHECK_PERFORMANCE clock_t startT = clock(); @@ -74,12 +79,17 @@ Eigen::MatrixXf JacobiProvider::computePseudoInverseJacobianMatrix(const Eigen:: case eSVD: { float pinvtoler = 0.00001f; + if (invParameter!=0.0f) + pinvtoler = invParameter; pseudo = MathTools::getPseudoInverse(m, pinvtoler); break; } case eSVDDamped: { - float pinvtoler = 0.00001f; + float pinvtoler = 1.0f; + if (invParameter!=0.0f) + pinvtoler = invParameter; + pseudo = MathTools::getPseudoInverseDamped(m,pinvtoler); break; } diff --git a/VirtualRobot/IK/JacobiProvider.h b/VirtualRobot/IK/JacobiProvider.h index b0d66f65ae184584ba689a1fc527e00765371853..85b98192699227e1026154802dc199180845a6de 100644 --- a/VirtualRobot/IK/JacobiProvider.h +++ b/VirtualRobot/IK/JacobiProvider.h @@ -60,6 +60,8 @@ public: virtual Eigen::MatrixXf getJacobianMatrix() = 0; virtual Eigen::MatrixXf getJacobianMatrix(SceneObjectPtr tcp) = 0; + + virtual Eigen::MatrixXf computePseudoInverseJacobianMatrix(const Eigen::MatrixXf &m, float invParameter) const; virtual Eigen::MatrixXf computePseudoInverseJacobianMatrix(const Eigen::MatrixXf &m) const; virtual Eigen::MatrixXf getPseudoInverseJacobianMatrix(); virtual Eigen::MatrixXf getPseudoInverseJacobianMatrix(SceneObjectPtr tcp); @@ -74,7 +76,7 @@ public: bool isInitialized(); /* - If set, a weigthed inverse Jacobian is computed. The weighting is only applied in eTranspose mode! + If set, a weighted inverse Jacobian is computed. The weighting is only applied in eTranspose mode! jointScaling.rows() must be nDoF Large entries result in small joint deltas. */