David, Further investigation found one more bug with gazebo. The torque values are continuously overwritten by zeros, ticketed here https://code.ros.org/trac/ros-pkg/ticket/4051 The fix in boxturtle has been checked in as r29314, will make a bug patch release later. thanks, John On Mon, May 3, 2010 at 1:22 PM, John Hsu wrote: > Hi David, > Thanks for the feedback, I see two (potential) issues here, > > - gazebo requires an iface internally, which I ticketed here > https://code.ros.org/trac/ros-pkg/ticket/4049. For now, if you add an > interface line to your controller, then things should work better > > > > true > > 15.0 > > box_force > object_link > * * > > > > > > > - 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: https://code.ros.org/trac/ros-pkg/ticket/4050). > > Thanks, > John > > On Mon, May 3, 2010 at 12:53 PM, David Ferguson wrote: > >> Hi, >> >> 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: >> >> This is a controller that collects data from a ROS topic and applies >> wrench to a body accordingly. >> >> Example Usage: >> \verbatim >> >> >> ... >> >> > plugin="libgazebo_ros_force.so"> >> true >> 15.0 >> box_force >> box_body >> >> >> \endverbatim >> >> To test it I essentially copied the tutorial showing how to use the iface >> plugin (sets a models position). My urdf file is below: >> >> > xmlns:controller=" >> http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" >> xmlns:interface=" >> http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" > >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> >> Gazebo/Black >> 10.0 >> 10.0 >> 10 >> 1.0 >> false >> 0.01 >> >> >> > plugin="libgazebo_ros_force.so"> >> true >> 15.0 >> box_force >> object_link >> >> >> >> >> 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? >> >> Thanks in advance for any help, >> >> David Ferguson >> >> _______________________________________________ >> ros-users mailing list >> ros-users@code.ros.org >> https://code.ros.org/mailman/listinfo/ros-users >> >> >