Hi Jim,<div><br></div><div>There are a couple of ways to simulate a spring in gazebo.  One example in ros uses a transmission as a "spring-like controller" (see <meta http-equiv="content-type" content="text/html; charset=utf-8"><a href="http://ros-users.122217.n3.nabble.com/Flexible-amp-remote-transmission-td1929619.html#a1937295">http://ros-users.122217.n3.nabble.com/Flexible-amp-remote-transmission-td1929619.html#a1937295</a> for an example of a torsional spring).  Alternatively, you can use a joint constraint to do the same thing.  To simulate a linear spring, you can define a prismatic joint with both upper and lower limits equal to 0.  This means any constraint violation produces an error correction force which is essentially the amount of constraint violation (x) multiplied by ODE's ERP parameter / dt (k).</div>

<div><br></div><div><meta http-equiv="content-type" content="text/html; charset=utf-8">Note that using a joint constraint to simulate spring will actually update joint force and compute equivalent compression distance within the same time step, whereas using a transmission controller as given in the example above, the spring force applied is computed using spring stretch from the last time step.</div>

<div><br></div><div>If you want to use the joint constraint approach, I recommend testing on a very simple setup and verifying the spring constant / forces first.<meta http-equiv="content-type" content="text/html; charset=utf-8"></div>

<div><br></div><div>Hope this helps.</div><div>John<br><br><div class="gmail_quote">On Sun, Jan 23, 2011 at 3:57 PM, Jim Rothrock <span dir="ltr"><<a href="mailto:jimrothrock52@gmail.com">jimrothrock52@gmail.com</a>></span> wrote:<br>

<blockquote class="gmail_quote" style="margin:0 0 0 .8ex;border-left:1px #ccc solid;padding-left:1ex;"><p>I have created a URDF file for a four-wheel-drive vehicle and am beginning to use it with Gazebo. Each shock absorber is a prismatic joint. Simulating the damping of a shock is easy; just set the joint's damping factor in a dynamics block. However, I don't know how to simulate the spring component of a shock. My only idea so far is to write a ROS node that subscribes to the joint's position topic. The node's loop gets the position, computes a force via Hooke's law, then applies a corresponding wrench to the joint. Is there a better way to simulate a spring in Gazebo? It seems that someone would have needed to simulate a shock absorber by now, but my searches didn't turn up any examples.<br>

<font color="#888888">

--<br>
Jim Rothrock | <a href="mailto:jimrothrock52@gmail.com" target="_blank">jimrothrock52@gmail.com</a><br>
Sent from my Android phone</font></p>
<br>_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org">ros-users@code.ros.org</a><br>
<a href="https://code.ros.org/mailman/listinfo/ros-users" target="_blank">https://code.ros.org/mailman/listinfo/ros-users</a><br>
<br></blockquote></div><br></div>