rbdl / rbdl-toolkit

Application for visualizing and working with rbdl models
European Union Public License 1.2
19 stars 11 forks source link

constraint questions #19

Closed jfslin closed 3 years ago

jfslin commented 3 years ago

@ju6ge a few questions from one of our student

1) A have a budget double pendulum working, but don't quite understand the joint specification. I understand that the 'joint_frame' entry is in terms of the parent's frame of reference, but how do you specify the joint location relative to the child or the child's center of mass? Or is it always at ( 0,0,0 ) for the child? 2) I noticed the example double pendulum uses constraints to pin the components together. Doesn't a joint already do that? 3) in the example double pendulum, both bodies are attached to the ROOT, shouldn't they be a kinetic chain ROOT->K1->K2? Or is that handled by the constraints?

ju6ge commented 3 years ago

Well as always there are multiple ways to achieve the same thing. For a simple double pendulum you should not need to use constraints. And it should be the correct solution to have Root->K1->K2. The general idea with constraints is to use them to describe your boundary conditions. You can for example use them to model closed loop systems that can't be easily described with the model tree. For this to work there are extra functions in RBDL to use constraints with IK and other rbdl functions.

Regarding the joint_frame model attribute. It is a lua table that can have two sub tables:

if neither is specified then default values are assumed. (r={0., 0., 0.}, E=IdentityMatrix)

idlebear commented 3 years ago

What specifies where the frame is mounted on the child? For instance, given a pendulum, the joint could be mounted on the end of the second body (k2 I guess), or at some offset from the end.

ju6ge commented 3 years ago

The short answer is to use the r={...} value in the joint_frame.

Here is an example frames part of a double pendulum model:

frames = {
    {
      name = "BASE",
      parent = "ROOT",
      joint_frame = {
        r = { 0, 0 , 1 },
      },
      visuals = {
        meshes.Base,
      },
    },
    {
      name = "UPPERARM",
      parent = "BASE",
      joint_frame = {
        r = { 0, 0 , 0 },
      },
      joint = {
        { 1, 0, 0, 0, 0, 0,},
      },
      visuals = {
        meshes.UpperArm,
        meshes.Joint_Start
      },
    },
    {
      name = "LOWERARM",
      parent = "UPPERARM",
      joint_frame = {
        r = { 0, 0 , -0.4 },
      },
      joint = {
        { 1, 0, 0, 0, 0, 0,},
      },
      visuals = {
        meshes.LowerArm,
        meshes.Joint_Start,
        meshes.Joint_End_LowerArm
      },
    },
  }

This is a double pendulum with a base link that is attached to the model root statically at (0, 0, 1) and can not move. Then the Upperarm is attached to the base at position (0., 0., 0.) since it is the first link. It has one dof to rotate around the x axis. The second link is then attached to the first link with position (0., 0., -0.4) also with one dof.

RBDL does not care how big the segments are, you could attach a body at any point relative to the parent body with any joint you like. The joint only describes what degrees of freedom a body has to move relative to the parent. To calculate Forces and torques the shape of any body also is not required since we are specifying the mass and inertia matrix directly. So it is up to the model creator to add visuals that appropriately show how the model looks.