Robotics StackExchange | Archived questions

joint damping has no effect

Hi there,

damping has no effect to avoid bouncing and flying of robots.I want to do like this but It doesn't work for me!

here is my SDF file. with a force of 0.051Nm and what ever damping value I set, alwayes the same behaviour.

<?xml version='1.0' ?>
<sdf version='1.4'>
<world name="default">
 <include>
   <uri>model://ground_plane</uri>
 </include>
<include>
   <uri>model://sun</uri>
 </include>
 <model name='0'>
<link name='1'>
    <pose>0.00503991 0.00855352 0.0245165 0 4.71239 0</pose>
    <inertial>
        <mass>0.05</mass>
        <inertia><ixx>0.000003333</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.000004271</iyy>
            <iyz>0</iyz><izz>0.000004271</izz>
        </inertia>
    </inertial>
    <collision name='collision'>
        <geometry>
            <box>
                <size>0.0125 0.01 0.01</size>
            </box>
        </geometry>
    </collision>
    <visual name='visual'>
        <geometry>
            <box>
                <size>0.0125 0.01 0.01</size>
            </box>
        </geometry>
    </visual>
</link>

<link name='2'>
    <pose>0.00503991 0.00855352 0.0370165 0 4.71239 0</pose>
    <inertial>
        <mass>0.05</mass>
        <inertia><ixx>0.000003333</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.000004271</iyy>
            <iyz>0</iyz><izz>0.000004271</izz>
        </inertia>
    </inertial>
    <collision name='collision'>
        <geometry>
            <box>
                <size>0.0125 0.01 0.01</size>
            </box>
        </geometry>
    </collision>
    <visual name='visual'>
    <geometry>
        <box>
            <size>0.0125 0.01 0.01</size>
        </box>
        </geometry>
    </visual>
</link>

<joint type="revolute" name="0_1">
    <pose>-0.00625 0 0 0 0 0</pose>
    <child>1</child>
    <parent>2</parent>
    <axis>
        <xyz>0 0 1</xyz>
        <limit>
            <lower>0.5</lower>
            <upper>-0.5</upper>
        </limit>
        <dynamics>
            <friction>0.05</friction>
            <damping>1000000000000000000000000000000000000000000000000000</damping>
        </dynamics>
    </axis>
    <physics>
        <ode>
            <implicit_spring_damper>1</implicit_spring_damper>
        </ode>
    </physics>
</joint>
<plugin name="controller" filename="build/libcontroller.so"/>
</model>
</world>
</sdf>

I have Gazebo version 6.1.0

Asked by djou07 on 2016-10-20 09:09:26 UTC

Comments

you realize it's spelled implicit_spring_damper, right?

Asked by Peter Mitrano on 2016-10-20 21:51:25 UTC

sorry, it was a typo...I'll correct it, still doesn't work!

Asked by djou07 on 2016-10-21 02:31:14 UTC

OMG you cannot set damping that high.... your model will expode O_O can you explain more specifically how you want the robot to behave?

Asked by Peter Mitrano on 2016-10-21 13:11:14 UTC

it is the same behaviour if I set damping to 0 or 10 or 100.... I have deferent robot shapes that I generate randomly, sometimes the robot is heavy and the force applied to the joint is big (30Nm) so robot starts to fly and bounce. I want whenever big is the force, the joint moves slowly but strong enought to lift other robot parts...I hope I well explained what I want.

Asked by djou07 on 2016-10-22 01:51:12 UTC

Your upper limit is lower than your lower limit, that's strange

Asked by eugene-katsevman on 2017-04-09 17:02:32 UTC

Answers

I removed the joint limite and it workd !! can someone explain why...

<limit>
    <lower>0.5</lower>
    <upper>-0.5</upper>
</limit>

Asked by djou07 on 2016-10-24 04:48:17 UTC

Comments