stack-of-tasks / pinocchio

A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
http://stack-of-tasks.github.io/pinocchio/
BSD 2-Clause "Simplified" License
1.78k stars 375 forks source link

API that fully update the robot's data #1377

Closed junhyeokahn closed 3 years ago

junhyeokahn commented 3 years ago

Hello, First of all, I appreciate your effort to maintain this nice repo.

I have a quick question about how Pinocchio updates the robot's properties. It looks like Pinocchio has multiple steps to update the robots quantities given q, qdot. For instance, forwardKinematics does not update the frames' placement, and therefore updateFramePlacements should be called afterward. Also, ccrba separately update centroidal quantities.

I am wondering is there any function where I could update all the robot's quantities at once and save results at Dataclass? If not, could you kindly explain what kind of APIs should be called in which order to correctly update the quantities?

jcarpent commented 3 years ago

There is the function computeAllTerms that does everything, except centroidal quantities. I will update it accordingly.

gabrielebndn commented 3 years ago

There is the function computeAllTerms that does everything, except centroidal quantities

Since @junhyeokahn mentioned frames, I will specify that computeAllTerms does not update frame placements either

BTW, if you just want to call forwardKinematics(model, data, q); and updateFramePlacements(model, data); all in one call and nothing else, there's framesForwardKinematics(model, data, q); doing it

jcarpent commented 3 years ago

Indeed, but it is easy to call updateFramePlacements(model, data) after calling computeAllTerms without additional burden. At this stage, there is no need to add updateFramePlacements in computeAllTerms

gabrielebndn commented 3 years ago

Indeed, but it is easy to call updateFramePlacements(model, data) after calling computeAllTerms without additional burden. At this stage, there is no need to add updateFramePlacements in computeAllTerms

There isn't of course, I was just saying it so that it would be clear to @junhyeokahn since he explicitly mentioned this

junhyeokahn commented 3 years ago

@jcarpent @gabrielebndn Thanks for the reply. So, after #1378 incorporated, I could probably call computeAllTerms and then updateFramePlacements, which will update all quantities.

Then, I might be able to access (correct me if I am wrong)

Follow up question is then, is there any way I can access the following quantities from data as well

I saw in the robot_wrapper these quantities are achieved from

One quick last question is how quickly conda (python bindings) reflects the changes in the master branch?

gabrielebndn commented 3 years ago

I saw in the robot_wrapper these quantities are achieved from

* `getFrameVelocity(model, data, frame_id)`,

* `getFrameJacobian(model, data, frame_id, pin.ReferenceFrame.LOCAL_WORLD_ALIGNED)`,

* `getFrameJacobianTimeVariation(model, data, frame_id, pin.ReferenceFrame.LOCAL_WORLD_ALIGNED)`,

* `computeCentroidalMapTimeVariation(model, data, q, qdot)`,
  but just wondering if I could access these quantities from `data` I as do for the other quantities.

Those are exactly the functions you need. Frame velocities, accelerations and Jacobians are not stored anywhere in data but they are computed on the fly (the same is true for joint Jacobians BTW).

The result of computeCentroidalMapTimeVariation is stored is data.dAg (you can check the online doc for that) and it is also computed by dccorba (the two algorithms seem to be equivalent, at least in terms of output)

jcarpent commented 3 years ago

Then, I might be able to access (correct me if I am wrong)

* centroidal quantities from `data.hg`, `data.Ag`, `data.Ig` without explicitly calling `ccrba`, YES

* com quantities from `data.com[0]`, `data.vcom[0]` without explicitly calling `centerOfMass`, YES

* com jacobian from `data.Jcom` instead of calling jacobianCenterOfMass```, YES

* nonlinear term from `data.nle` instead of calling `nonLinearEffects`, YES

* gravity term from `data.g` instead of calling `computeGeneralizedGraivity`, YES

* mass matrix from `data.M` instead of calling `crba`, YES

* frame placement from `data.oMf` instead of calling `updateFramePlacement`. NO!!!

You should still call updateFramePlacements(model,data) which pretty much easy.

jcarpent commented 3 years ago

The question is why do you need dJ/dt or dAg/dt?

jcarpent commented 3 years ago

One quick last question is how quickly conda (python bindings) reflects the changes in the master branch?

For each new release, conda is compiling and making it available to anyone on conda-forge. What is your timeline? In any cases, it is very easy to install Pinocchio from sources under a conda environment.

junhyeokahn commented 3 years ago

@gabrielebndn @jcarpent Thanks for clarifying all the questions It resolves all of my questions!

What is your timeline?

I don't have a strict timeline but I was just wondering.

I use dJ/dt to control operational space task in acceleration level (using the equation xddot = dJ/dT * qdot + J * qddot).

jcarpent commented 3 years ago

This is a drift term, so you don't need to compute this term at all. Assuming qddot == 0, you get your quantity for free from forward kinematics. Just call computeAllTerms, it is all what you need!

jcarpent commented 3 years ago

Solved by #1378.