David,<br><br>Thanks for uncovering the issues with that particular plugin, but I think I forgot to mention a very important thing...  I think I'd approach this problem differently.  A better way to apply torque on the wheels is to use the pr2_controllers stack -- by adding a simple transmission and using the gazebo_ros_controller_manager plugin.<br>

I recommend taking a look at the package/example pr2_examples_gazebo/single_link.launch, and replacing the position controller with an effort controller.<br><br>John<br><br><br><br><div class="gmail_quote">On Mon, May 3, 2010 at 12:53 PM, David Ferguson <span dir="ltr"><<a href="mailto:dhf@andrew.cmu.edu">dhf@andrew.cmu.edu</a>></span> wrote:<br>

<blockquote class="gmail_quote" style="margin: 0pt 0pt 0pt 0.8ex; border-left: 1px solid rgb(204, 204, 204); padding-left: 1ex;">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>_______________________________________________<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>