1 #include "pinocchio/parsers/sample-models.hpp" 2 #include "pinocchio/spatial/explog.hpp" 3 #include "pinocchio/algorithm/kinematics.hpp" 4 #include "pinocchio/algorithm/jacobian.hpp" 5 #include "pinocchio/algorithm/joint-configuration.hpp" 7 int main(
int ,
char ** )
17 const double eps = 1e-4;
19 const double DT = 1e-1;
20 const double damp = 1e-6;
26 typedef Eigen::Matrix<double, 6, 1> Vector6d;
46 JJt.noalias() = J * J.transpose();
47 JJt.diagonal().array() +=
damp;
48 v.noalias() = - J.transpose() * JJt.ldlt().solve(err);
51 std::cout <<
i <<
": error = " << err.transpose() << std::endl;
55 std::cout <<
"Convergence achieved!" << std::endl;
57 std::cout <<
"\nWarning: the iterative algorithm has not reached convergence to the desired precision" << std::endl;
59 std::cout <<
"\nresult: " << q.transpose() << std::endl;
60 std::cout <<
"\nfinal error: " << err.transpose() << std::endl;
void integrate(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v, const Eigen::MatrixBase< ReturnType > &qout)
Integrate a configuration vector for the specified model for a tangent vector during one unit time...
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
SE3GroupAction< D >::ReturnType actInv(const D &d) const
by = aXb.actInv(ay)
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
ToVectorConstReturnType toVector() const
int nv
Dimension of the velocity vector space.
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
void computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex jointId, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store t...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > VectorXd
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.