leggedrobotics / ocs2

Optimal Control for Switched Systems
https://leggedrobotics.github.io/ocs2
BSD 3-Clause "New" or "Revised" License
836 stars 221 forks source link

How to get the jacobian matrix? #98

Closed ppap36 closed 5 months ago

ppap36 commented 5 months ago

Is your feature request related to a problem? Please describe. I hope to obtain the Jacobian matrix in the velocity constraint, but after using the following loop output code, although the manipulator is in motion, its output remains unchanged. I want to know why.

  auto& model = pinocchioInterfacePtr_->getModel();
  auto& data = pinocchioInterfacePtr_->getData();
  auto id = model.getBodyId("panda_hand");
  ocs2::vector_t q;  // pinocchio joint positions
  ocs2::matrix_t J1 = ocs2::matrix_t::Zero(6,model.nq);
  ocs2::matrix_t J2 = ocs2::matrix_t::Zero(6,model.nq);
  //pinocchio::forwardKinematics(model, data, q);
  pinocchio::updateFramePlacements(model, data);
  pinocchio::computeJointJacobians(model, data);
  const ocs2::vector_t posa = data.oMf[id].translation();
  //id = id +2;
  pinocchio::getFrameJacobian(model,data,id,pinocchio::ReferenceFrame::LOCAL_WORLD_ALIGNED,J1);
  pinocchio::getJointJacobian(model,data,id,pinocchio::ReferenceFrame::LOCAL_WORLD_ALIGNED,J2);
  std::cout<<"Hello!I AM pos!"<<std::endl;
  std::cout<<posa<<std::endl;
  std::cout<<"Hello!I AM jacobian 1!"<<std::endl;
  std::cout<<J1<<std::endl;
  std::cout<<"Hello!I AM jacobian 2!"<<std::endl;
  std::cout<<J2<<std::endl;

Another question, I want to use this code to get the manipulator's end effector velocity

endEffectorKinematicsPtr_->getVelocity(state,input).front()

however, it always gives me zero, but the manipulator is moving!