Home | Tutorials | Wiki | Issues
Ask Your Question
1

Simulating Springs

asked 2012-11-14 00:23:57 -0500

mdedonato gravatar image

I am looking to simulate a spring on a rotational joint in Gazebo. My goal would be to have an arm maintain a position when no external force is applied, but give when a force is applied. I see the "dampening" feature under the joint, axis properties, but I cannot find a spring feature. Is there a way to do this?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2012-11-14 14:07:47 -0500

hsu gravatar image

take a look at this spring test world

it checks equivalence between erp/cfm and spring constants.

see video of it in action. Left most sphere uses a plugin that simulates spring forces, right 4 spheres have prismatic joints with 0 limits with different combinations of cfm and erp. The world file contains explanation on the underlying equations.

edit flag offensive delete link more
0

answered 2012-11-14 10:35:51 -0500

Erik Stoltenborg gravatar image

updated 2012-11-14 10:38:38 -0500

Hi,

As far as i know, there is no such joint in gazebo (ODE/Bullet), however you could write a simple model plugin to achieve this.

In this plugin, you can use the following code (its better to define variables and pointers in load, but to get the idea):

    public: void OnUpdate()
    {
      double rest_angle = 0;
      double stiffness = 2;
      physics::JointPtr springjoint;
       springjoint =  this->model->GetJoint(int _joint_index);
      double current_angle = springjoint->GetAngle(int _index).Radian());
      springjoint->SetForce(int _index, (rest_angle-current_angle)*stiffness);
    }

Use this code, along with these tutorials and the API and you should be fine!

edit flag offensive delete link more
Login/Signup to Answer

Question Tools

2 followers

Stats

Asked: 2012-11-14 00:23:57 -0500

Seen: 3,601 times

Last updated: Nov 14 '12