[ros-users] Gazebo Vehicle Simulation
John Hsu
johnhsu at willowgarage.com
Mon May 3 21:03:46 UTC 2010
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 <johnhsu at willowgarage.com> 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
>
> <gazebo>
> <controller:gazebo_ros_force name="box_force_controller" plugin="libgazebo_ros_force.so">
> <alwaysOn>true</alwaysOn>
>
> <updateRate>15.0</updateRate>
>
> <topicName>box_force</topicName>
> <bodyName>object_link</bodyName>
> * <interface:audio name="dummy_iface"/>*
>
> </controller:gazebo_ros_force>
>
>
> </gazebo>
>
> - 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 <dhf at andrew.cmu.edu>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
>> <model:physical name="box_model">
>> <body:empty name="box_body">
>> ...
>> </body:empty>
>> <controller:gazebo_ros_force name="box_force_controller"
>> plugin="libgazebo_ros_force.so">
>> <alwaysOn>true</alwaysOn>
>> <updateRate>15.0</updateRate>
>> <topicName>box_force</topicName>
>> <bodyName>box_body</bodyName>
>> </controller:gazebo_ros_force>
>> </model:phyiscal>
>> \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:
>>
>> <robot name="object_model"
>> xmlns:controller="
>> http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
>> xmlns:interface="
>> http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" >
>> <!-- urdf requires at least one joint and one link, so here's the joint
>> -->
>> <joint name="my_mug_joint" type="floating" >
>> <!-- axis is in the parent link frame coordintates -->
>> <axis xyz="0 0 0" />
>> <parent link="world" />
>> <child link="object_link" />
>> <!-- initial pose of my_mug joint/link in the parent frame coordiantes
>> -->
>> <origin xyz="0 0 0" rpy="0 0 0" />
>> </joint>
>> <!-- one floating link -->
>> <link name="object_link">
>> <inertial>
>> <mass value="1"/>
>> <origin xyz="0 0 0.0"/>
>> <inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/>
>> </inertial>
>> <visual>
>> <origin rpy="0 0 0" xyz="0 0 0.0"/>
>> <geometry>
>> <box size="1.0 1.0 1.0"/>
>> </geometry>
>> </visual>
>> <collision>
>> <origin rpy="0 0 0" xyz="0 0 0.0"/>
>> <geometry>
>> <box size="1.0 1.0 1.0"/>
>> </geometry>
>> </collision>
>>
>> </link>
>> <gazebo reference="object_link">
>> <material>Gazebo/Black</material>
>> <mu1>10.0</mu1>
>> <mu2>10.0</mu2>
>> <kp>10</kp>
>> <kd>1.0</kd>
>> <turnGravityOff>false</turnGravityOff>
>> <dampingFactor>0.01</dampingFactor>
>> </gazebo>
>> <gazebo>
>> <controller:gazebo_ros_force name="box_force_controller"
>> plugin="libgazebo_ros_force.so">
>> <alwaysOn>true</alwaysOn>
>> <updateRate>15.0</updateRate>
>> <topicName>box_force</topicName>
>> <bodyName>object_link</bodyName>
>> </controller:gazebo_ros_force>
>> </gazebo>
>> </robot>
>>
>> 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 at code.ros.org
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>>
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100503/be6135f1/attachment-0003.html>
More information about the ros-users
mailing list