Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

What is the definition of joint Jacobian and frame Jacobian? #1455

Closed
kaixqu opened this issue May 29, 2021 · 7 comments
Closed

What is the definition of joint Jacobian and frame Jacobian? #1455

kaixqu opened this issue May 29, 2021 · 7 comments
Assignees

Comments

@kaixqu
Copy link

kaixqu commented May 29, 2021

Hi,

I am recently trying to use the Jacobian function from Pinocchio. But I must say, the documentation is quite misleading to me. I tried to look into the issues, but still, things are still not that clear.

I think when saying Jacobian (or geometric Jacobian), we mean the relations between the velocity of the end-effector and the velocity of the joints that supports this end-effector.

For instance, if we have an 8-DoF manipulator, then the Jacobian should be of size 6 * 8, where column j corresponds to the velocity of the end-effector when joint j has unit velocity. In other words, for a manipulator with the following kinematic tree structure (0 -> 1 -> 2 -> ... -> 7 -> 8 -> End-effector), then there is only one Jacobian that express how the joint affects the leaf (ee).

My confusion is then why do we have computeJointJacobian whose functionality is Computes the Jacobian of a specific joint frame expressed in the local frame of the joint and store the result in the input argument J.

And then, what is the purpose of getJointJacobian and getFrameJacobian? How are they related? The former one Computes the Jacobian of a specific joint frame expressed either in the world (rf = WORLD) frame or in the local frame (rf = LOCAL) of the joint, and the latter one Computes the Jacobian of a specific Frame expressed in the desired reference_frame given as argument.

From what I learned, I only know the Jacobian that I described, and by the name of the Pinocchio function, I guess I should then call getFrameJacobian?

In this issue: #418 (comment), there is a comment "There is no sense in having getFrameJacobian() in world frame, as, in the world frame, joint jacobian and frame jacobian are equal." Why is that? What is the definition of Jacobian?

Thank you in advance for your clarification!

@proyan
Copy link
Member

proyan commented May 31, 2021

Hi Kaixian,
It looks like the main problem with understanding the documentation that you have, is

  1. between API intended with compute and get functions
  2. Use of the world frame to denote the "frame of reference" and also the class which denotes some required placements/inertias on the kinematic tree.

Let's look at point (2) first.
The Frame Class in pinocchio denotes a placement (with or without associated inertia) that is FIXED w.r.t. a parent joint. So the kinematic tree is composed of a chain of joints, and the Frame objects are FIXED on top of individual joints.

Now let's look at point (1):
If you are given a configuration q, then in order to compute the jacobian, you would have to go through all the parents, get their placements, and use them to compose the J matrix. To do this, you go through the kinematic tree of the robot.

Now, imagine that you have already done that for a joint j. If the joint j is the parent of a Frame object f, and I ask you to get me the jacobian at the placement of the frame f. Since you already went through the kinematic tree once when computing J, it is redundant for you to do that. The jacobian at the frame f can be found by only looking at J and the relationship between Frame f and Joint j, i.e. jMf (the relative placement of Frame f w.r.t. Joint j).

This is the difference between compute and get. You need compute when you need to use the configuration variable q, and you use get to obtain values that were computed by compute

There are the following functions that are defined for dealing with jacobians:

  1. computeJointJacobians : computes ALL jacobians
  2. computeJointJacobian: computes only one joint jacobian
  3. computeFrameJacobian: computes only one frame jacobian
  4. getJointJacobian: If computeJointJacobians is already called, it gives the joint jacobian given by joint id j
  5. getFrameJacobian: If computeJointJacobians is already called, it gives the frame jacobian given by frame id f.

The API of the compute functions require q, v and so on to compute the values. The get functions normally only require the internal model information (such as "which joint id" or "which frame id").

I hope that is clear enough

@kaixqu
Copy link
Author

kaixqu commented May 31, 2021

Hi Rohan,

Thanks for the quick and detailed reply! So I assume what I described above should be done by first calling computeJointJacobians, and then getFrameJacobian with the frameId of that specific End-effector frame. Please correct me if I am wrong.

jointJacobian refers to the Jacobian of each joint frame, whereas the frameJacobian is the Jacobian of all the frames.

I agree that the Jacobian of each joint frame is enough for calculating the Jacobian of its children frame, because the velocity of that joint frame is enough for calculating the velocity of every frame fixed w.r.t. that link (assuming that link is a rigid body). I guess this calculation is done in getFrameJacobian.

However, why this comment says "There is no sense in having getFrameJacobian() in world frame, as, in the world frame, joint jacobian and frame jacobian are equal." Why is that? How could the Jacobian of joint frame be the same as that of its children frame? Is there something I am missing?

Thanks! :)

@proyan
Copy link
Member

proyan commented May 31, 2021

  1. You need to call computeJointJacobians before you call a get function.
  2. You would have to define the end-effector frame if it is not yet defined. If your "end-effector frame" co incides with the joint (e.g., the wrist of a robot), then you could simply use the getJointJacobian, otherwise you would need getFrameJacobian
  3. Only for the case of WORLD reference frame , there is the following relation:
    getFrameJacobian(model, data, frame_id, WORLD) == getJointJacobian(model, data, joint_id, WORLD), if joint_id corresponds to the parent joint of frame frame_id.

As I told you above, the frame is FIXED w.r.t the parent joint. If you do the math (I won't do it here), it is easy to see that when looking through the WORLD frame of reference, jMf does not play any role in the computation of the jacobian. However, the following relation isn't true when looking through LOCAL and LOCAL_WORLD_ALIGNED frames.

How could the Jacobian of joint frame be the same as that of its children frame? Is there something I am missing?

The "jacobian of the joint frame" is not what we are talking about here. What we are talking about is "the jacobian of a frame which is fixed w.r.t a joint" vs "jacobian of the joint". And that too in a specific ReferenceFrame WORLD. See my point (2) above about the difference between a "frame of reference", i.e. reference frame and the Frame Class.

@kaixqu
Copy link
Author

kaixqu commented May 31, 2021

First, I have to say I am really confused about your statement on

jMf does not play any role in the computation of the jacobian

Without copying equations from lecture note or somewhere else, can we just look at a 2D inverted pendulum (with only one joint hinged at the origin). The Jacobian of that joint frame should be something like [0; 0; 1], as the origin of the joint is not moving. However, the tip of that inverted pendulum definitely have something else for translational part, instead of just zeros. And this is definitely related to jMf, or just the length of that pendulum.

Last but not the least, you said that jointJacobian is not the "jacobian of the joint frame". Could you please tell me the definition of joint Jacobian (jacobian of the joint) and frame Jacobian? I could not find any definition for it online. From my point of view, jacobian provides the relation between joint velocities and end-effector velocities.

Thanks!

@jcarpent
Copy link
Contributor

jcarpent commented May 31, 2021

However, why this comment says "There is no sense in having getFrameJacobian() in world frame, as, in the world frame, joint jacobian and frame jacobian are equal." Why is that? How could the Jacobian of joint frame be the same as that of its children frame? Is there something I am missing?

I fact, when computing the Jacobians in the WORLD frame, meaning the velocity field associated to the point coincident with the world center, but moving with the body, both Frame and Joint Jacobians expressed in the WORLD coordinate system will refer to the same quantity, as mentioned by @proyan.

This mixing does not appear when one expresses the quantity in their LOCAL or LOCAL_WORLD_ALIGNED coordinate systems.

@proyan
Copy link
Member

proyan commented May 31, 2021

@kaixqu

I feel that we are going in circles a bit. I suggest you give it some time to sink in, try a bit in python (it is easy), and then come back. Here is a script for you to play:

import example_robot_data
import pinocchio
robot = example_robot_data.loadTalos()
pinocchio.computeJointJacobians(robot.model, robot.data, pinocchio.randomConfiguration(robot.model)) # compute jacobians for a random configuration
Jf = pinocchio.getFrameJacobian(robot.model, robot.data, 100, pinocchio.WORLD) #for a random frame id 100
Jj = pinocchio.getJointJacobian(robot.model, robot.data, robot.model.frames[100].parent, pinocchio.WORLD) #parent of the frame 100
(Jj == Jf).all()

Try different combinations, and look at the basic spatial algebra concepts used in pinocchio from here: https://stack-of-tasks.github.io/pinocchio/assets/math-concepts.pdf. This should be enough for you to understand practically what is happening
I'll close this issue

@proyan proyan closed this as completed May 31, 2021
@XuanLin
Copy link

XuanLin commented Sep 24, 2023

However, why this comment says "There is no sense in having getFrameJacobian() in world frame, as, in the world frame, joint jacobian and frame jacobian are equal." Why is that? How could the Jacobian of joint frame be the same as that of its children frame? Is there something I am missing?

I fact, when computing the Jacobians in the WORLD frame, meaning the velocity field associated to the point coincident with the world center, but moving with the body, both Frame and Joint Jacobians expressed in the WORLD coordinate system will refer to the same quantity, as mentioned by @proyan.

This mixing does not appear when one expresses the quantity in their LOCAL or LOCAL_WORLD_ALIGNED coordinate systems.

Hi,

My apologies for posting a comment in this closed issue. I want to check if my understanding is correct. In the figure below, I draw a 2-dof manipulator with theta_1 and theta_2, and three frames: joint JxJy, user-defined FxFy, and world WxWy. For joint Jacobians, we use V_J (V_J=J*dq). For frame Jacobians, we use V_F. My understanding for WORLD Jacobian is, we imagine expanding the link to cover the origin of the world, then use the velocity V_W expressed in the world frame WxWy. On the other hand, for LOCAL, we use V_J or V_F (depending on joint or frame Jacobian), expressed in local frame (JxJy or FxFy). For LOCAL_ALIGNED, we use V_J or V_F, but still expressed in WORLD frame. Is that correct?

image_50367745

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants