Go to the documentation of this file.
    9 int main(
int , 
char ** )
 
   19   const double eps = 1e-4;
 
   21   const double DT = 1e-1;
 
   22   const double damp = 1e-6;
 
   28   typedef Eigen::Matrix<double, 6, 1> Vector6d;
 
   30   Eigen::VectorXd 
v(
model.nv);
 
   51     JJt.noalias() = 
J * 
J.transpose();
 
   52     JJt.diagonal().array() += 
damp;
 
   53     v.noalias() = -
J.transpose() * JJt.ldlt().solve(
err);
 
   56       std::cout << 
i << 
": error = " << 
err.transpose() << std::endl;
 
   61     std::cout << 
"Convergence achieved!" << std::endl;
 
   66       << 
"\nWarning: the iterative algorithm has not reached convergence to the desired precision" 
   70   std::cout << 
"\nresult: " << 
q.transpose() << std::endl;
 
   71   std::cout << 
"\nfinal error: " << 
err.transpose() << std::endl;
 
  
void manipulator(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool mimic=false)
Create a 6-DOF kinematic chain shoulder-elbow-wrist.
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.
void Jlog6(const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog)
Derivative of log6.
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 computeJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const JointIndex joint_id, 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, 6, 6, Options > Matrix6
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
The 6d jacobian type (temporary)
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
Return the neutral configuration element related to the model configuration space.
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:18