-
Notifications
You must be signed in to change notification settings - Fork 391
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
Comments
Hi Kaixian,
Let's look at point (2) first. Now let's look at point (1): Now, imagine that you have already done that for a joint This is the difference between There are the following functions that are defined for dealing with jacobians:
The API of the I hope that is clear enough |
Hi Rohan, Thanks for the quick and detailed reply! So I assume what I described above should be done by first calling
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 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! :) |
As I told you above, the frame is
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. |
First, I have to say I am really confused about your statement on
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 Last but not the least, you said that Thanks! |
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. |
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 |
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? |
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 isComputes 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
andgetFrameJacobian
? How are they related? The former oneComputes 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 oneComputes 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!
The text was updated successfully, but these errors were encountered: