Gazebo | Ignition | Community
Ask Your Question
0

Creating a Constant Force Spring

asked 2018-08-29 16:14:51 -0600

gambini gravatar image

updated 2018-08-31 13:25:53 -0600

Hi all,

I am trying to make a prismatic joint into a constant force spring.

Does there exist a way to do this using Gazebo parameters?

If not, I am trying to write my own C++ code to read in the force on the joint/link and add a 200N constant force against it; however, I have been unable to read the force being applied. There seems to be gazebo::physics::joint::getForceTorque() and gazebo::physics::joint::getForce(), but a look at the source code shows these to be incomplete:

https://bitbucket.org/osrf/gazebo/src... https://bitbucket.org/osrf/gazebo/src...

Is there something I may be missing? Has anyone else attempted to build something similar before?

Thank you in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-08-31 09:36:49 -0600

updated 2018-08-31 15:20:38 -0600

Have you tried using the SDF - Joint - Stiffness Element?

Example:

<joint name="gas_spring_joint" type="prismatic">
  <parent>cylinder</parent>
  <child>piston</child>
  <pose>0 0 0 0 0 0</pose>
  <axis>
    <limit>
      <lower>-0.1</lower>
      <upper>0.1</upper>
    </limit>
    <xyz>0.0 0.0 1.0</xyz>
    <dynamics>
      <spring_stiffness>2500</spring_stiffness>
      <spring_reference>0.06</spring_reference>
      <damping>20.0</damping>
      <friction>0.75</friction>
    </dynamics>
    <use_parent_model_frame>0</use_parent_model_frame>
  </axis>
  <physics>
    <ode>
      <implicit_spring_damper>1</implicit_spring_damper>
      <cfm_damping>1</cfm_damping>
      <limit>
        <cfm>0</cfm>
        <erp>0.2</erp>
      </limit>
    </ode>
  </physics>
</joint>

Also, see http://answers.gazebosim.org/question...

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-08-29 16:14:51 -0600

Seen: 3,637 times

Last updated: Aug 31 '18