diff --git a/src/common_fc.cpp b/src/common_fc.cpp index 295d30f4cb6d0ea4a0b1b83cf61fc9417eed376c..7633a2547384d95d4b5590cc38a0abdeab904ba1 100644 --- a/src/common_fc.cpp +++ b/src/common_fc.cpp @@ -29,11 +29,10 @@ Eigen::MatrixXd CCommon_Fc::WeightInvJac(const Eigen::MatrixXd& J, const Eigen:: } // weighting matrix - // Eigen::MatrixXd Winv = CalcPinv(W); - // Eigen::MatrixXd temp = J*Winv*J.transpose(); - // Eigen::MatrixXd J_inverse = Winv*J.transpose()*CalcPinv(temp); - J_inverse = J.transpose(); - + Eigen::MatrixXd Winv = CalcPinv(W); + Eigen::MatrixXd temp = J*Winv*J.transpose(); + Eigen::MatrixXd J_inverse = Winv*J.transpose()*CalcPinv(temp); + return J_inverse; } diff --git a/src/common_fc.h b/src/common_fc.h index fdf1e5fd157d6f6fb61cab22cc8ce851f6b545d7..2523d17912b14ee6b5015a874fcf7353bae39116 100644 --- a/src/common_fc.h +++ b/src/common_fc.h @@ -61,10 +61,9 @@ class CCommon_Fc */ template<typename _Matrix_Type_> static _Matrix_Type_ CalcPinv(const _Matrix_Type_ &a, double epsilon = std::numeric_limits<double>::epsilon()) { - //Eigen::JacobiSVD< _Matrix_Type_ > svdd(a, Eigen::ComputeThinU | Eigen::ComputeThinV); - //double tolerance = epsilon * std::max(a.cols(), a.rows()) *svdd.singularValues().array().abs()(0); - //_Matrix_Type_ mpinv = svdd.matrixV() * (svdd.singularValues().array().abs() > tolerance).select(svdd.singularValues().array().inverse(), 0).matrix().asDiagonal() * svdd.matrixU().adjoint(); - _Matrix_Type_ mpinv = a.transpose(); + Eigen::JacobiSVD< _Matrix_Type_ > svdd(a, Eigen::ComputeThinU | Eigen::ComputeThinV); + double tolerance = epsilon * std::max(a.cols(), a.rows()) *svdd.singularValues().array().abs()(0); + _Matrix_Type_ mpinv = svdd.matrixV() * (svdd.singularValues().array().abs() > tolerance).select(svdd.singularValues().array().inverse(), 0).matrix().asDiagonal() * svdd.matrixU().adjoint(); return mpinv; } diff --git a/src/tasks/cog.cpp b/src/tasks/cog.cpp index 9283a370d15d6d95f8e9a319d2c279d6321bee9d..799497bd8acc5e1cd516fd87633e6eb0fab3b47d 100644 --- a/src/tasks/cog.cpp +++ b/src/tasks/cog.cpp @@ -169,8 +169,7 @@ void CTaskCOG::TaskErrorJacFull(UAM::CArm& arm, const UAM::CHT& HT, Eigen::Matri JG.block(0,4,2,arm.nj)=Jacob_temp.block(0,0,2,arm.nj); - //JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG); - JG_pseudo = JG.transpose(); + JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG); } void CTaskCOG::TaskErrorJac(UAM::CArm& arm, const UAM::CHT& HT, Eigen::MatrixXd& cog_PGxy, Eigen::MatrixXd& cog_arm, Eigen::MatrixXd& sigmaG, Eigen::MatrixXd& JG, Eigen::MatrixXd& JG_pseudo, UAM::ArmCogData& arm_cog_data) @@ -192,8 +191,7 @@ void CTaskCOG::TaskErrorJac(UAM::CArm& arm, const UAM::CHT& HT, Eigen::MatrixXd& JG.block(0,4,1,arm.nj)=2*cog_PGxy.transpose()*Jacob_temp.block(0,0,2,arm.nj); - //JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG); - JG_pseudo = JG.transpose(); + JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG); } } // End of UAM namespace \ No newline at end of file diff --git a/src/tasks/ir.cpp b/src/tasks/ir.cpp index 2437b852168d9de7fb26c01036807012110bc83a..584d4c964db2dae39ddf5425106e49fe551d782a 100644 --- a/src/tasks/ir.cpp +++ b/src/tasks/ir.cpp @@ -44,9 +44,8 @@ void CTaskIR::TaskErrorJac(const int& arm_dof, const double& inf_rad, const Eige } // } - // Eigen::MatrixXd Hinv = UAM::CCommon_Fc::CalcPinv(H); - Eigen::MatrixXd Hinv = H.transpose(); - + Eigen::MatrixXd Hinv = UAM::CCommon_Fc::CalcPinv(H); + // weighting matrix Eigen::MatrixXd temp = JIR*Hinv*JIR.transpose(); JIR_pseudo = Hinv*JIR.transpose()*temp.transpose(); diff --git a/src/tasks/jl.cpp b/src/tasks/jl.cpp index 4e8f5047d7b291292bf64555b5d1d48d223959a3..9b972d6def93f450f3a2d67c76de204e0cb314ef 100644 --- a/src/tasks/jl.cpp +++ b/src/tasks/jl.cpp @@ -47,8 +47,7 @@ void CTaskJL::TaskErrorJac(UAM::CArm& arm, const Eigen::MatrixXd& jntlim_pos_des JL.block(0,4,1,arm.nj) = pow_n*Jtemp.transpose(); // Task Jacobian Pseudo-inverse - //JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); - JL_pseudo = JL.transpose(); + JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); } void CTaskJL::TaskErrorJacFull(UAM::CArm& arm, const Eigen::MatrixXd& jntlim_pos_des, Eigen::MatrixXd& jntlim_pos_error, Eigen::MatrixXd& sigmaL, Eigen::MatrixXd& JL, Eigen::MatrixXd& JL_pseudo) @@ -70,8 +69,7 @@ void CTaskJL::TaskErrorJacFull(UAM::CArm& arm, const Eigen::MatrixXd& jntlim_pos } // Task Jacobian Pseudo-inverse - //JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); - JL_pseudo = JL.transpose(); + JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); } } // End of UAM namespace \ No newline at end of file