Skip to content
Snippets Groups Projects
Commit c186abd8 authored by asantamaria's avatar asantamaria
Browse files

merged dev branch and changed again to CalcPinv for master

parent 1e6da700
No related branches found
No related tags found
No related merge requests found
...@@ -29,11 +29,10 @@ Eigen::MatrixXd CCommon_Fc::WeightInvJac(const Eigen::MatrixXd& J, const Eigen:: ...@@ -29,11 +29,10 @@ Eigen::MatrixXd CCommon_Fc::WeightInvJac(const Eigen::MatrixXd& J, const Eigen::
} }
// weighting matrix // weighting matrix
// Eigen::MatrixXd Winv = CalcPinv(W); Eigen::MatrixXd Winv = CalcPinv(W);
// Eigen::MatrixXd temp = J*Winv*J.transpose(); Eigen::MatrixXd temp = J*Winv*J.transpose();
// Eigen::MatrixXd J_inverse = Winv*J.transpose()*CalcPinv(temp); Eigen::MatrixXd J_inverse = Winv*J.transpose()*CalcPinv(temp);
J_inverse = J.transpose();
return J_inverse; return J_inverse;
} }
......
...@@ -61,10 +61,9 @@ class CCommon_Fc ...@@ -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()) 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); Eigen::JacobiSVD< _Matrix_Type_ > svdd(a, Eigen::ComputeThinU | Eigen::ComputeThinV);
//double tolerance = epsilon * std::max(a.cols(), a.rows()) *svdd.singularValues().array().abs()(0); 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 = svdd.matrixV() * (svdd.singularValues().array().abs() > tolerance).select(svdd.singularValues().array().inverse(), 0).matrix().asDiagonal() * svdd.matrixU().adjoint();
_Matrix_Type_ mpinv = a.transpose();
return mpinv; return mpinv;
} }
......
...@@ -169,8 +169,7 @@ void CTaskCOG::TaskErrorJacFull(UAM::CArm& arm, const UAM::CHT& HT, Eigen::Matri ...@@ -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.block(0,4,2,arm.nj)=Jacob_temp.block(0,0,2,arm.nj);
//JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG); JG_pseudo = UAM::CCommon_Fc::CalcPinv(JG);
JG_pseudo = JG.transpose();
} }
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) 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& ...@@ -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.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 = UAM::CCommon_Fc::CalcPinv(JG);
JG_pseudo = JG.transpose();
} }
} // End of UAM namespace } // End of UAM namespace
\ No newline at end of file
...@@ -44,9 +44,8 @@ void CTaskIR::TaskErrorJac(const int& arm_dof, const double& inf_rad, const Eige ...@@ -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 = UAM::CCommon_Fc::CalcPinv(H);
Eigen::MatrixXd Hinv = H.transpose();
// weighting matrix // weighting matrix
Eigen::MatrixXd temp = JIR*Hinv*JIR.transpose(); Eigen::MatrixXd temp = JIR*Hinv*JIR.transpose();
JIR_pseudo = Hinv*JIR.transpose()*temp.transpose(); JIR_pseudo = Hinv*JIR.transpose()*temp.transpose();
......
...@@ -47,8 +47,7 @@ void CTaskJL::TaskErrorJac(UAM::CArm& arm, const Eigen::MatrixXd& jntlim_pos_des ...@@ -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(); JL.block(0,4,1,arm.nj) = pow_n*Jtemp.transpose();
// Task Jacobian Pseudo-inverse // Task Jacobian Pseudo-inverse
//JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL);
JL_pseudo = JL.transpose();
} }
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) 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 ...@@ -70,8 +69,7 @@ void CTaskJL::TaskErrorJacFull(UAM::CArm& arm, const Eigen::MatrixXd& jntlim_pos
} }
// Task Jacobian Pseudo-inverse // Task Jacobian Pseudo-inverse
//JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL); JL_pseudo = UAM::CCommon_Fc::CalcPinv(JL);
JL_pseudo = JL.transpose();
} }
} // End of UAM namespace } // End of UAM namespace
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment