Closed costashatz closed 8 years ago
The most common bottleneck for simulation speed is collision detection. If you can briefly describe how your simulator performs collision detection, we may be able to identify the key factor that is impacting performance.
For example: Does your simulator only use primitive shapes? If so, which ones? Are you using a specific collision detection library, such as ODE's collision detector?
The default collision detector for DART is FCL, and I believe we convert certain primitive types (like spheres/ellipsoids) into meshes so that we get better collision information for them (because of a known issue in FCL where it only reports one contact point for primitive shape collisions, even if there are multiple contact points). This use of meshes instead of primitives could have a huge impact on performance.
DART allows the collision detector to be switched out, so you could replace the FCL collision detector with your own. Let me know if you'd like more details on how to do that.
Thank you for the super fast answer.
For example: Does your simulator only use primitive shapes? If so, which ones? Are you using a specific collision detection library, such as ODE's collision detector?
Yes, we are using primitive shapes only. You can see here. And we are using ODE's collision detector.
DART allows the collision detector to be switched out, so you could replace the FCL collision detector with your own. Let me know if you'd like more details on how to do that.
I see that you have Bullet support on collision detection. Are you doing the same thing as with FCL (converting primitive types to meshes)? If not, is Bullet collision detection faster? How can I switch to that?
I see that you have Bullet support on collision detection. Are you doing the same thing as with FCL (converting primitive types to meshes)? If not, is Bullet collision detection faster? How can I switch to that?
I found out how to change to Bullet collision detection and it was almost twice faster in our case. So, this should be the issue for the speed. Many thanks!
You didn't answer to my question regarding computing energy consumption of motors(joints) though. Any insight on that one? Thanks!
Energy isn't my expertise, but I think it will depend on whether you're talking about joint energy (i.e. the energy of the generalized coordinates) or actuator power consumption (i.e. the electrical energy per second that the motor is consuming).
DART has some convenience functions that give the total kinetic and potential energy of a system, but I don't think these would help you.
I believe you should be able to find references for computing power consumption using quantities that DART does provide, such as generalized forces and generalized displacements. For the power consumption of an actuator, you will have to factor in some motor properties as well. Those motor properties cannot be handled natively by DART at the moment.
There are actually some discussions about implementing an "Actuator" class in DART which would likely be used to compute the exact things you're asking for. If you come up with an API design and a prototype implementation of an Actuator class, you would be more than welcome to share it as a Github issue, and we can incorporate it into the final design.
Energy isn't my expertise either. I found the following procedure for revolute joints:
This can done with dart, since dart provides the forces of each joint, the positions of each joint and the time step. Also, note that this is only for revolute joints (as far as I understand - maybe it works with all 1-dof joints) and does not take into account any motor properties. If we want to take into account a specific motor efficiency (and/or other properties) we need to to do more work. If you know any better, don't hesitate to correct me.
When I have some time, I will look at implementing an "Actuator" class, because it seems useful.
The power consumption of one joint, would be: ε = ε + dθ*dt. This is a recursive addition (emulating an integration).
I suspect there is an error or two in this expression. (1) It's not factoring in torque, and (2) It implies that if a joint is being held at a fixed angle, then it is not consuming any energy, even if a non-zero torque is required to hold it there (because it may need to resist gravity or some other external force).
If you're hoping to compute the power consumption of the actuator (rather than the rate of total energy change of the joint), then I believe you will need to compute the current and voltage that the motor needs in order to produce the torque that the joint is experiencing, and then use P = IV. This would need to account for any gearing attached to the motor and would depend on various properties of the motor itself (which you should be able to find in a spec sheet for the motor). To be fully accurate, you would also want to consider whether the motor is stalled (for a robot, it will probably be stalled most of the time).
If you don't know what kind of motor you would use, then I'd suggest just picking some motor+gearbox specs whose stall torques would match or slightly exceed what you'd expect for the maximum torque of each joint. You could probably pick some motor specs arbitrarily if your algorithm only cares about relative performance, but an arbitrary set of specs might not be good at capturing the correct magnitude of difference between trials.
I suspect there is an error or two in this expression. (1) It's not factoring in torque
Yes. Because I had a typo. I wanted to write: ε = ε + dθ*dT (where dT is the difference in torques). Of course, I am not sure if this is correct either.
(2) It implies that if a joint is being held at a fixed angle, then it is not consuming any energy, even if a non-zero torque is required to hold it there (because it may need to resist gravity or some other external force).
But how can a joint stay in a fixed angle? I have PD controllers and there should always be some small deviation in the joint angles between time steps.
If you're hoping to compute the power consumption of the actuator (rather than the rate of total energy change of the joint), then I believe you will need to compute the current and voltage that the motor needs in order to produce the torque that the joint is experiencing, and then use P = IV. This would need to account for any gearing attached to the motor and would depend on various properties of the motor itself (which you should be able to find in a spec sheet for the motor). To be fully accurate, you would also want to consider whether the motor is stalled (for a robot, it will probably be stalled most of the time).
This is true, but I believe that the rate of total energy change of the joint could suffice for our purposes.
I wanted to write: ε = ε + dθ*dT (where dT is the difference in torques).
This would still have the issue where holding the joint at a fixed position will be seen as consuming no energy, even if the motor needs to generate a torque to hold it there (in order to resist gravity or external forces).
But how can a joint stay in a fixed angle? I have PD controllers and there should always be some small deviation in the joint angles between time steps.
If your controller is given a fixed reference position for a long enough period of time, the PD controller will converge to a fixed position. If it is only PD and not PID and there are external forces (such as gravity) present, then the position it converges to will be offset from the reference position, but it will converge nonetheless. And even if it does not fully converge in finite time, your computation will still be getting scaled by a rapidly shrinking displacement value to the point that you might as well be integrating a value of zero.
but I believe that the rate of total energy change of the joint could suffice for our purposes.
This seems unlikely to me, if only because I can't think of an application where change in total energy would be a useful metric. If the goal of your algorithm is to make decisions based on power efficiency, then you'd definitely want the power consumption of the actuator, not the change in total energy at the joint. To illustrate why, consider this example:
Suppose your algorithm is trying to choose the most efficient walking gait by running many thousands of trials. In one trial, the humanoid walker holds its arms up in front of itself like a zombie, which means the arms are spending energy the whole time resisting gravity. In another trial, the humanoid walker has its arms hanging down at its sides where they are not spending any energy to fight gravity. If you use the total change in energy metric, then both of these trials would have equal value, even though one of them is clearly expending more motor power than the other.
To avoid needing to account for motor or gearing properties, you could just integrate the magnitude of torque over time, and that should be a reasonable approximation of motor power consumption.
Thanks for the super fast answer and guidelines! They are very helpful!
But how can a joint stay in a fixed angle? I have PD controllers and there should always be some small deviation in the joint angles between time steps.
If we assume that the actual controller of the real hardware is able to control the joint to stay in a fixed angle, then we can make it happenes in the simulation as well. DART's Joint supports several actuator types. You may have used FORCE
type, which is default. If you change the actuator type of the joint to LOCKED
, for example, the joint will perfectly stay in the current angle. Internally, LOCKED
joint is regarded as an kinematic joint. This means the kinematic joint values such as joint positions, velocities, and accelerations now become the input for the joint, and the forward dynamics algorithm computes joint forces that is required to achieve the kinematic joint values.
Similarly, there are VELOCITY
and SERVO
types that both of them take desired joint velocities. The differences of the two types is that VELOCITY
always achieves the desired velocity regardless how much joint force is required, whereas SERVO
tries to achieve the desired velocity with given joint for limits. If SERVO
joint need more forces than the limits then it will fail to achieve the desired velocity just like a real servo motor.
SERVO
actuator type is not implemented yet but I'm working on it. It's expected to be finished within this week.
If we assume that the actual controller of the real hardware is able to control the joint to stay in a fixed angle, then we can make it happenes in the simulation as well.
The thing is that we cannot assume it without some tolerance. There's always some small perturbation and the controller tries to compensate for that. Anyway, I get what you are saying and I agree with it.
If you change the actuator type of the joint to LOCKED, for example, the joint will perfectly stay in the current angle. Internally, LOCKED joint is regarded as an kinematic joint.
But my intention is not to use kinematic joints.
I am interested in the SERVO
joint. Is this one kinematic too?
I am interested in the SERVO joint. Is this one kinematic too?
SERVO
joint is a dynamic joint. In the point of dynamics algorithm, it is basically similar to FORCE
joint; the input is joint force and output is joint acceleration. The difference is that a SERVO
joint has properties of desired velocity and force limits, and the constraint solver of DART computes and applies constraint impulses for the servo joint that is required to achieve the desired velocity.
SERVO joint is a dynamic joint. In the point of dynamics algorithm, it is basically similar to FORCE joint; the input is joint force and output is joint acceleration. The difference is that a SERVO joint has properties of desired velocity and force limits, and the constraint solver of DART computes and applies constraint impulses for the servo joint that is required to achieve the desired velocity.
Nice! I'll keep an eye to check when you have finished it. It seems that this is the joint that we should be using in our simulations.
Thanks!
Hello,
We are implementing robotics evolutionary algorithms and so far we've been using our own custom physics simulator (robdyn1) to produce the desired simulations. As we are extending our robot repository (we already have 2 hexapods, one mobile base+manipulator and we are waiting a humanoid), we think it's time to change to a better and more configurable physics engine/simulator. DART provides an easier to use and more robust toolkit than ODE for robotics, while also maintaining the ability to write custom code (which is crucial for us). So I wanted to ask you some questions:
Many thanks in advance!