Closed lmontaut closed 3 years ago
Hi @Diiso,
First of all, it is better if you use Box-FDDP since its greater globalization strategy. For more details read https://arxiv.org/pdf/2010.00411.pdf
Second, Box-FDDP (or Box-DDP) is clamping the control commands, not contact/impulse forces. A way to handle your problem is by designing high impact velocities. You could also explore the idea to penalize a high impulse force. However, I am afraid that finding those values will require a lot of tuning.
Most of our legged robotics examples use impulse dynamics. Using them is as simple as using the contact dynamics!
Finally, you cannot optimize the horizon. This remains a research work that could be easily build on top of Crocoddyl.
Personally, I have tried to incorporate the dt
into the control vector.
However, this doesn't work well!
The people that success on this approach always use linear (or appr. linear) dynamics!
Hi @cmastalli , thank you for your reply. I will have a look at biped.py
to see how the impulse dynamics is dealt with in the case of legged robots and apply that to my hammer example.
I don't understand how incorporating dt
in the control vector influences the horizon. When we define a shooting problem, the number of nodes is independant of dt
right ?
problem = crocoddyl.ShootingProblem(x0, [running_model] * T, terminal_model)
You could incorporate by defining a tailored integrated action model. Then, you could use Box-FDDP to define bounds on dt. However, from my experience, it won't work well. It increases the number of iterations, and the optimized dt doesn't seem to be meaningful.
If you want to let more about my results, we could have a private discussion.
Are these answers solving this issue? If so, could you close it?
Yes, thank you @cmastalli. I will close this issue.
Sorry, I may have closed the issue too soon.
There is something I don't understand in biped.py
example.
In the function CreateImpulseModel
of the gait problem class, the impulse model is applied to the supporting foot:
# Creating a 6D multi-contact model, and then including the supporting foot
impulseModel = crocoddyl.ImpulseModelMultiple(self.state)
for i in supportFootIds:
supportContactModel = crocoddyl.ImpulseModel6D(self.state, i)
impulseModel.addImpulse(self.rmodel.frames[i].name + "_impulse", supportContactModel)
Why is the impulse model applied on the supporting foot? I expected it to be applied to the foot which is not supported and which will make contact with the floor.
The ImpulseModel6D
creates a constraint in our impulse dynamics. See Eq. (6) in https://cmastalli.github.io/publications/crocoddyl20icra.pdf
It is an impulse dynamics what you are defining here.
Let me know if you have further doubts
Hi,
I want to use Crocoddyl to control a hammer in order to hammer a nail when the friction is high enough for the hammer to need multiple hits before the nail is entirely down (I am using BoxDDP to limit the maximum force to control the hammer). Is there a simple example in Crocoddyl which deals with impact dynamics ?
I have another question: is it possible to optimize for the horizon of the shooting problem (number of nodes in the shooting problem)?
Thanks.