David,<br><br>Further investigation found one more bug with gazebo.  The torque values are continuously overwritten by zeros, ticketed here<br>
<a href="https://code.ros.org/trac/ros-pkg/ticket/4051">https://code.ros.org/trac/ros-pkg/ticket/4051</a><br>The fix in boxturtle has been checked in as r29314, will make a bug patch release later.<br>
<br>thanks,<br>John<br><br><div class="gmail_quote">On Mon, May 3, 2010 at 1:22 PM, John Hsu <span dir="ltr"><<a href="mailto:johnhsu@willowgarage.com">johnhsu@willowgarage.com</a>></span> wrote:<br><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;">

Hi David,<br>Thanks for the feedback, I see two (potential) issues here,<br><ul><li>gazebo requires an iface internally, which I ticketed here <a href="https://code.ros.org/trac/ros-pkg/ticket/4049" target="_blank">https://code.ros.org/trac/ros-pkg/ticket/4049</a>.  For now, if you add an interface line to your controller, then things should work better<br>


<pre><div class="im">    <gazebo><br>        <controller:gazebo_ros_force name="box_force_controller" plugin="libgazebo_ros_force.so"><br>         <alwaysOn>true</alwaysOn><br>

         <updateRate>15.0</updateRate><br>
         <topicName>box_force</topicName><br>         <bodyName>object_link</bodyName><br></div><b>         <interface:audio name="dummy_iface"/></b><div class="im"><br>        </controller:gazebo_ros_force><br>


    </gazebo><br></div></pre></li><li>another issue that might come up:  if the world update rate differs from the force plugin update rate, force application will be skipped in the intermediate time steps.  For example, if world is updating at 1kHz and your controller has an updateRate of 100Hz, the desired force on the body is applied only 1 out of 10 simulation updates, resulting in what looks like a 1/10th smaller force than desired.  So I recommend changing updateRate to match (or be greater than) your world update rate for now.  (I also ticketed this here: <a href="https://code.ros.org/trac/ros-pkg/ticket/4050" target="_blank">https://code.ros.org/trac/ros-pkg/ticket/4050</a>).<br>


</li></ul>Thanks,<br>John<br><br><div class="gmail_quote"><div><div></div><div class="h5">On Mon, May 3, 2010 at 12:53 PM, David Ferguson <span dir="ltr"><<a href="mailto:dhf@andrew.cmu.edu" target="_blank">dhf@andrew.cmu.edu</a>></span> wrote:<br>

</div></div><blockquote class="gmail_quote" style="border-left: 1px solid rgb(204, 204, 204); margin: 0pt 0pt 0pt 0.8ex; padding-left: 1ex;"><div><div></div><div class="h5">
Hi,<br><br>I am trying to write create a gazebo simulation of a 4 wheeled vehicle (think golf cart). I am having an issue with trying to create forces in the simulation. I want to apply a torque the rear wheels (equivalent to pressing the gas pedal). I can't figure out however how to use the gazebo plugin which is supposed to apply the force. In the .h file for the plugin it says to use it as such:<br>




<br>  This is a controller that collects data from a ROS topic and applies wrench to a body accordingly.<br><br>  Example Usage:<br>  \verbatim<br>  <model:physical name="box_model"><br>    <body:empty name="box_body"><br>




     ...<br>    </body:empty><br>    <controller:gazebo_ros_force name="box_force_controller" plugin="libgazebo_ros_force.so"><br>        <alwaysOn>true</alwaysOn><br>        <updateRate>15.0</updateRate><br>




        <topicName>box_force</topicName><br>        <bodyName>box_body</bodyName><br>    </controller:gazebo_ros_force><br>  </model:phyiscal><br>  \endverbatim<br><br>To test it I essentially copied the tutorial showing how to use the iface plugin (sets a models position). My urdf file is below:<br>




<br><robot name="object_model"<br>       xmlns:controller="<a href="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" target="_blank">http://playerstage.sourceforge.net/gazebo/xmlschema/#controller</a>"<br>




       xmlns:interface="<a href="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" target="_blank">http://playerstage.sourceforge.net/gazebo/xmlschema/#interface</a>" ><br>  <!-- urdf requires at least one joint and one link, so here's the joint --><br>




  <joint name="my_mug_joint" type="floating" ><br>    <!-- axis is in the parent link frame coordintates --><br>    <axis xyz="0 0 0" /><br>    <parent link="world" /><br>




    <child link="object_link" /><br>    <!-- initial pose of my_mug joint/link in the parent frame coordiantes --><br>    <origin xyz="0 0 0" rpy="0 0 0" /><br>  </joint><br>




  <!-- one floating link --><br>  <link name="object_link"><br>    <inertial><br>      <mass value="1"/><br>      <origin xyz="0 0 0.0"/><br>      <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/><br>




    </inertial><br>    <visual><br>      <origin rpy="0 0 0" xyz="0 0 0.0"/><br>      <geometry><br>        <box size="1.0 1.0 1.0"/><br>      </geometry><br>




    </visual><br>    <collision><br>      <origin rpy="0 0 0" xyz="0 0 0.0"/><br>      <geometry><br>        <box size="1.0 1.0 1.0"/><br>      </geometry><br>




    </collision><br><br>  </link><br>  <gazebo reference="object_link"><br>    <material>Gazebo/Black</material><br>    <mu1>10.0</mu1><br>    <mu2>10.0</mu2><br>




    <kp>10</kp><br>    <kd>1.0</kd><br>    <turnGravityOff>false</turnGravityOff><br>    <dampingFactor>0.01</dampingFactor><br>  </gazebo><br>    <gazebo><br>        <controller:gazebo_ros_force name="box_force_controller" plugin="libgazebo_ros_force.so"><br>




         <alwaysOn>true</alwaysOn><br>         <updateRate>15.0</updateRate><br>         <topicName>box_force</topicName><br>         <bodyName>object_link</bodyName><br>        </controller:gazebo_ros_force><br>




    </gazebo><br></robot><br><br>I then have a python script publishing a wrench message to the box_force topic however no matter what settings I use it never seems to actually affect the box in the simulation. Am I going about this completely wrong? Is there a flag I'm not setting?<br>




<br>Thanks in advance for any help,<br><font color="#888888"><br>David Ferguson<br>
</font><br></div></div>_______________________________________________<br>
ros-users mailing list<br>
<a href="mailto:ros-users@code.ros.org" target="_blank">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>
</blockquote></div><br>