dartsim / dart

DART: Dynamic Animation and Robotics Toolkit
http://dartsim.github.io/
BSD 2-Clause "Simplified" License
893 stars 286 forks source link

getForces #569

Closed costashatz closed 8 years ago

costashatz commented 8 years ago

Hello,

I am simulating a hexapod robot (18dof). I want to get my robot's force readings on every joint. I tried using the following:

None of them seem to work. I am getting all zeros. Any ideas?

mxgrey commented 8 years ago

I'll have to ask a few questions in order to help you debug your situation.

costashatz commented 8 years ago

Are you using Gazebo while simulating, or are you using DART directly?

DART directly.

If you're using DART directly, are you calling these functions within a simulation loop? If you're running a dart::simulation::World using DART directly, could you toss the World into a dart::gui::SimWindow and provide a screenshot of what the simulation looks like?

I am using dart::simulation::World. The robot moves fine (simple gaits etc). No weird things.

Does your simulation world have any kind of object representing the ground or floor?

Yes, I have a floor.

I found 2 possible solutions:

But I am getting different results. With the first solution I am getting 0 force for the first 6 DOF (6d pose), which makes sense, whereas with the second one I am not. What should I use?

costashatz commented 8 years ago

To make it more clear:

mxgrey commented 8 years ago

You'll almost certainly want to use the first solution, because that will accurately represent the joint forces that were present during the simulation. The default behavior for step is to reset all the joint commands (which may include joint forces) to zero so that your system is passive by default. To ensure that you get the joint forces after a step is complete, you'll want to pass in false. At that point, there should be no need to call computeInverseDynamics, although if you do call that function, then you'll probably want to pass in true for all its parameters so that it accounts for everything that is present in the simulation (like external forces).

costashatz commented 8 years ago

Thank you very much! Once again you've been very helpful.

omerkayan commented 1 year ago

Hi @costashatz,

I have similar problem with you. Could you please help me? I am always getting zeros.

I have a skeleton and I want to read forces by skeleton for two nodes and one joint. Node1: FemurL Node2: TibiaL Joint1: Revolute joint between FemurL and TibiaL

</Node>
<Node name="TibiaL" parent="FemurL" >
    <Body type="Box" mass="3.0" size="0.1198 0.4156 0.1141 " contact="Off" color="0.6 0.6 1.5 1.0" obj="L_Tibia.obj">
        <Transformation linear="0.9994 0.0348 -0.0030 -0.0349 0.9956 -0.0871 -0.0 0.0872 0.9962 " translation="0.0928 0.3018 -0.0341 "/>
    </Body>
    <Joint type="Revolute" axis ="1.0 0.0 0.0" bvh="Character1_LeftLeg" lower="0.0" upper="2.3">
        <Transformation linear="1.0 0.0 0.0 0.0 1.0 0.0 0.0 0.0 1.0" translation="0.0995 0.5387 -0.0103 "/>
    </Joint>
</Node>

This is my way to read forces in Joint1: force_on_joint1= *(mCharacter->GetSkeleton()->getBodyNode("TibiaL")->getChildJoint(0)->getForces().data());