loco-3d / crocoddyl

Crocoddyl is an optimal control library for robot control under contact sequence. Its solver is based on various efficient Differential Dynamic Programming (DDP)-like algorithms
BSD 3-Clause "New" or "Revised" License
839 stars 172 forks source link

Model multiple point-contacts per foot #703

Closed julesser closed 4 years ago

julesser commented 4 years ago

Hi all, I am trying to model multiple point-contacts per foot in the context of bipedal walking. Currently it seems shooting problem can not be solved properly (plotConvergence graphics stay all empty, Robot does not move at all). To this end, I've modified the biped_utils as follows:

  1. Pass the main frame (for foot tracking) and the contact frames (4 additional per foot) to the utils: def __init__(self, rmodel, rightFoot, leftFoot, rightFootContacts, leftFootContacts)
  2. Modify the walking problem to consider the contact frames for the supportingFoot and the main frame for the swingingFoot, e.g. rStep = self.createFootstepModels(comRef, [rfPos0], 0.5 * stepLength, stepHeight, timeStep, stepKnots, self.lfContactIds, [self.rfId])
  3. Don't touch createSwingFootModel(), which e.g. is supposed to yield for a step node in:
    • a contact model containing 8 contact items (4 for each foot)
    • a cost model containing one CoM tracking item, one foot tracking item, 8 friction cone items, state/ctrl reg items

The questions:

cmastalli commented 4 years ago

About your developed method Your method is mathematically wrong within this context. Each point-contact introduces a 3d constraint Jacobian (or 6d if you didn't modify it inside biped_utils script), i.e. 12 (or 18) constraints . For instance, in the double support phase, you will have a total of 24 (or 36) constraints but the system DoFs is 18. In conclusion, you are over-constraining the dynamical systems. See the equations of this paper for more details: https://cmastalli.github.io/publications/crocoddyl20icra.pdf

About the example model As you see, I encoded a 6d Jacobian, which constraints rotation too. The only missing part of this model is that we need to keep the CoP inside the foot support. Unfortunately, this cost function remains to be developed. Is this feature important for you now?

I will definitively develop this cost function, but it is not yet in the TOP of my TODO list. If this is important, I could commit to it. Alternatively, you are also welcome to make this contribution.

julesser commented 4 years ago

In conclusion, you are over-constraining the dynamical systems.

Thanks for pointing this out. Actually I thought these redundant constraints could be handled by the dynamic solvers. For now, we will simply stick with modelling one point contact per foot.

Is this feature important for you now?

No, currently this is not crucial for us.