Gazebo | Ignition | Community
Ask Your Question
1

How to move a prismatic (or other) joint to negative limits?

asked 2016-11-10 09:45:14 -0600

imlearning gravatar image

updated 2016-11-17 09:13:00 -0600

When creating a prismatic joint between two links, it seems as though that initial distance between the links behaves as a "hard stop" for the joint.

If treating it like a spring, the initial position seems to be the "fully compressed" representation and all spring effects extend from that distance.

Is all this true? Does the "lower limit" = the initial distance between the links?

And if so, is there a way to work around this and move the joint lower than the lower limit (to bring the links closer together than their initial positions)?

(Note: This is an extension of this question.)

Example Code:                         
<model name='Pris_1'>
<link name='rod'>
  <pose frame=''>2.7415 -3.31431 1.27606 -1.5708 -0 -0.37111</pose>
  <inertial>
    <mass>1</mass>
    <inertia>
      <ixx>0.145833</ixx>
      <ixy>0</ixy>
      <ixz>0</ixz>
      <iyy>0.145833</iyy>
      <iyz>0</iyz>
      <izz>0.125</izz>
    </inertia>
    <pose frame=''>0 0 0 0 -0 0</pose>
  </inertial>
  <self_collide>0</self_collide>
  <kinematic>1</kinematic>
  <visual name='visual'>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <cylinder>
        <radius>0.003</radius>
        <length>0.1</length>
      </cylinder>
    </geometry>
    <cast_shadows>1</cast_shadows>
    <transparency>0</transparency>
  </visual>
  <collision name='collision'>
    <laser_retro>0</laser_retro>
    <max_contacts>10</max_contacts>
    <pose frame=''>0 0 0 0 -0 0</pose>
    <geometry>
      <cylinder>
        <radius>0.0025</radius>
        <length>0.1</length>
      </cylinder>
    </geometry>
    <surface>
      <friction>
        <ode>
          <mu>1</mu>
          <mu2>1</mu2>
          <fdir1>0 0 0</fdir1>
          <slip1>0</slip1>
          <slip2>0</slip2>
        </ode>
        <torsional>
          <coefficient>1</coefficient>
          <patch_radius>0</patch_radius>
          <surface_radius>0</surface_radius>
          <use_patch_radius>1</use_patch_radius>
          <ode>
            <slip>0</slip>
          </ode>
        </torsional>
      </friction>
      <bounce>
        <restitution_coefficient>0</restitution_coefficient>
        <threshold>1e+06</threshold>
      </bounce>
      <contact>
        <collide_without_contact>0</collide_without_contact>
        <collide_without_contact_bitmask>1</collide_without_contact_bitmask>
        <collide_bitmask>1</collide_bitmask>
        <ode>
          <soft_cfm>0</soft_cfm>
          <soft_erp>0.2</soft_erp>
          <kp>1e+13</kp>
          <kd>1</kd>
          <max_vel>0.01</max_vel>
          <min_depth>0</min_depth>
        </ode>
        <bullet>
          <split_impulse>1</split_impulse>
          <split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
          <soft_cfm>0</soft_cfm>
          <soft_erp>0.2</soft_erp>
          <kp>1e+13</kp>
          <kd>1</kd>
        </bullet>
      </contact>
    </surface>
  </collision>
</link>
<model name='rope'>
  <pose frame=''>3.00263 -3.42589 1.02758 -3.0832 -0.749567 2.76636</pose>
  <link name='pivot'>
    <pose frame=''>0.4048 0 0 0 -0 0</pose>
    <inertial>
      <mass>0.1</mass>
      <inertia>
        <ixx>0.01</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>0.01</iyy>
        <iyz>0</iyz>
        <izz>0.01</izz>
      </inertia>
    </inertial>
    <collision name='pivot_collision'>
      <geometry>
        <mesh>
          <scale>0.1 0.1 0.1</scale>
          <uri>model://ball.stl</uri>
        </mesh>
      </geometry>
      <surface>
        <contact>
          <ode>
            <min_depth>0.005</min_depth>
          </ode>
        </contact>
        <friction>
          <ode>
            <mu>1</mu>
            <mu2>1</mu2>
          </ode>
          <torsional>
            <ode/>
          </torsional>
        </friction>
        <bounce/>
      </surface>
      <max_contacts>10</max_contacts>
    </collision>
    <visual name='pivot_vis'>
      <geometry>
        <mesh>
          <scale>0.1 0.1 0.1</scale>
          <uri>model://ball.stl</uri>
        </mesh>
      </geometry>
    </visual>
    <self_collide>0</self_collide>
    <kinematic>0</kinematic>
  </link>
 </model>
 <model name='cylinder'>
  <link name='link_0'>
    <pose frame=''>5e-06 3e-06 0.5 1.5708 -0 0</pose>
    <inertial>
      <mass>1</mass>
      <inertia>
        <ixx>0.166667 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-11-16 13:09:02 -0600

updated 2016-11-16 13:09:28 -0600

You can set the lower and upper limits of a joint (including prismatic) using the following tags:

http://sdformat.org/spec?ver=1.6&elem...

If this wasn't what you were asking comment on this answer

edit flag offensive delete link more

Comments

The problem I am having is that there seems to be a hard limit to the travel of the joint independent from the lower limit value (based on the initial distance b/w the two links connected by the joint). Ex: If I allow the joint to behave like a damped spring, the two links never get closer than their initial position. Setting the lower limit to an exaggerated negative value doesn't even seem to solve the problem. If setting the lower limit should work, do you have suggestions for how use?

imlearning gravatar imageimlearning ( 2016-11-16 16:49:56 -0600 )edit

Maybe you have self-collide on? Collision model could be wrong? You'll need need provide an SDF demonstrationg the problem for me to help further.

Peter Mitrano gravatar imagePeter Mitrano ( 2016-11-16 23:44:08 -0600 )edit

Please let me know if you notice anything in the collision/ contact dynamics. The goal is to get rope::pivot closer to cylinder::link_0 after simulation start.

imlearning gravatar imageimlearning ( 2016-11-17 09:16:56 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-11-10 09:45:14 -0600

Seen: 902 times

Last updated: Nov 17 '16