Re: [ros-users] URDF Gazebo problem

Top Page
Attachments:
Message as email
+ (text/plain)
+ rover.xml (text/xml)
Delete this message
Reply to this message
Author: Andreas Vogt
Date:  
To: ros-users
Subject: Re: [ros-users] URDF Gazebo problem
Hi John,

Thanks your example worked but still I don't know how the information
goes from xml file to the controller.
Still there are some questions. How I can use this:


     <!-- PR2_ACTARRAY -->
       <controller:gazebo_ros_controller_manager
name="gazebo_ros_controller_manager"
plugin="libgazebo_ros_controller_manager.so">
         <alwaysOn>true</alwaysOn>
         <updateRate>100.0</updateRate>
         <interface:audio 
name="gazebo_ros_controller_manager_dummy_iface" />
       </controller:gazebo_ros_controller_manager>


       <!-- gazebo_ros_p3d for position groundtruth -->
       <controller:gazebo_ros_p3d name="p3d_link1_controller"
plugin="libgazebo_ros_p3d.so">
           <alwaysOn>true</alwaysOn>
           <updateRate>100.0</updateRate>
           <bodyName>link1</bodyName>
           <topicName>link1_pose</topicName>
           <frameName>map</frameName>
           <interface:position name="p3d_link1_position"/>
       </controller:gazebo_ros_p3d>
   </gazebo>
   <!-- mechanism controls -->
   <include filename="./single_link.transmission.xacro" />


for my model (see attached file rover.xml)?

And the problem with rviz still exist. All components are merged
together at one point and the model is white.

Thanks

Andreas


John Hsu schrieb:
> Hi Andreas,
> A simple example can be found here:
>
> roslaunch pr2_examples_gazebo single_link.launch
> roslaunch pr2_controller_manager controller_manager.launch
>
> then you can see your link in rviz
>
> rosrun rviz rviz
>
> Set fixed and target frames to /world and try sending a command to the
> controller by
>
> rostopic pub /test_controller/command std_msgs/Float64 0.1
>
> you should see the link approach target joint position in gazebo and
> in rviz.
> John
>
> On Thu, May 6, 2010 at 12:29 AM, Andreas Vogt <
> <mailto:andreas.vogt@dfki.de>> wrote:
>
>
>     Hi,
>     Can anyone give me a short example (with one or two joints) how to
>     use URDF together with gazebo?
>     There are a lot of examples for the pr2 robot but no example how
>     to start with a simple and small system from the scratch.
>     I have a robot description in xml. I did all the parse and
>     checking stuff described in the tutorials. But now I want to read
>     and write angles to these joints which are described in the XML
>     file and want to see the movements in the simulation. How can I do
>     that?

>
>     Thanxs for any help
>     Andreas

>
>     I spawn the XML model of the robot sucessfully into gazebo but
>     when I start rviz all the tf's are missing.

>
>
>
>     _______________________________________________
>     ros-users mailing list
>      <mailto:ros-users@code.ros.org>
>     https://code.ros.org/mailman/listinfo/ros-users

>
>
> ------------------------------------------------------------------------
>
> _______________________________________________
> ros-users mailing list
>
> https://code.ros.org/mailman/listinfo/ros-users
>



--

Andreas Vogt
Logistics and Production Robotics

DFKI Bremen
Robotics Innovation Center
Robert-Hooke-Straße 5
28359 Bremen, Germany

Phone: +49 (0)421 218-64140
Fax: +49 (0)421 218-64150
E-Mail:

  Weitere Informationen: http://www.dfki.de/robotik
  -----------------------------------------------------------------------
  Deutsches Forschungszentrum fuer Kuenstliche Intelligenz GmbH
  Firmensitz: Trippstadter Straße 122, D-67663 Kaiserslautern
  Geschaeftsfuehrung: Prof. Dr. Dr. h.c. mult. Wolfgang Wahlster
  (Vorsitzender) Dr. Walter Olthoff
  Vorsitzender des Aufsichtsrats: Prof. Dr. h.c. Hans A. Aukes
  Amtsgericht Kaiserslautern, HRB 2313
  Sitz der Gesellschaft: Kaiserslautern (HRB 2313)
  USt-Id.Nr.:    DE 148646973
  Steuernummer:  19/673/0060/3



<?xml version="1.0"?>
<robot name="rover"

       xmlns:xi="http://www.w3.org/2001/XInclude"
       xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
       xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
       xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
       xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
       xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
       xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
       xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
       xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
       xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
       xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
       xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics">


    <link name="platform">
        <inertial>
            <origin xyz="0 0 0.630"/>
            <mass value="30"/>
            <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <geometry>
                <box size="0.515 0.956 0.100"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0"/>
                  <geometry>
                    <box size="0.515 0.956 0.100"/>
                  </geometry>
            </collision>
    </link>


    <link name="verticalaxis1">
        <inertial>
            <origin xyz="0.2575 0.478 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.200"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector1">
        <inertial>
            <origin xyz="0.2575 0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel1">
        <inertial>
            <origin xyz="0.3305 0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>



    <link name="verticalaxis2">
        <inertial>
            <origin xyz="0.2575 -0.478 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.410"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector2">
        <inertial>
            <origin xyz="0.2575 -0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel2">
        <inertial>
            <origin xyz="0.3305 -0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>



    <link name="verticalaxis3">
        <inertial>
            <origin xyz="0.2575 0 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.410"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector3">
        <inertial>
            <origin xyz="0.2575 0 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel3">
        <inertial>
            <origin xyz="0.3305 0 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>



    <link name="verticalaxis4">
        <inertial>
            <origin xyz="-0.2575 0 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.410"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector4">
        <inertial>
            <origin xyz="-0.2575 0 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel4">
        <inertial>
            <origin xyz="-0.3305 0 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>



    <link name="verticalaxis5">
        <inertial>
            <origin xyz="-0.2575 -0.478 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.410"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector5">
        <inertial>
            <origin xyz="-0.2575 -0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel5">
        <inertial>
            <origin xyz="-0.3305 -0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>



    <link name="verticalaxis6">
        <inertial>
            <origin xyz="-0.2575 0.478 0.115" rpy="0 0 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 -0.115" rpy="0 0 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.410"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.410"/>
                  </geometry>
            </collision>
    </link>


    <link name="connector6">
        <inertial>
            <origin xyz="-0.2575 0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.010" length="0.073"/>
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
                  <geometry>
                    <cylinder radius="0.010" length="0.073"/>
                  </geometry>
            </collision>
    </link>


    <link name="wheel6">
        <inertial>
            <origin xyz="-0.3305 0.478 0" rpy="0 1.6 0"/>
            <mass value="1"/>
            <inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/> 
        </inertial>
        <visual>
            <origin xyz="0 0 0" rpy="0 1.6 0"/>
            <geometry>
                <cylinder radius="0.110" length="0.086"/>
            </geometry>
        </visual>
        <collision>
                  <origin xyz="0 0 0" rpy="0 1.57079 0"/>
                  <geometry>
                    <cylinder radius="0.110" length="0.086"/>
                  </geometry>
            </collision>
    </link>






    <joint name="joint_p-a1" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis1"/>
        <origin xyz="0.2575 0.478 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c1" type="revolute">
        <parent link="verticalaxis1"/>
        <child link="connector1"/>
        <origin xyz="0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w1" type="continuous">
        <parent link="connector1"/>
        <child link="wheel1"/>
        <origin xyz="0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>


    <joint name="joint_p-a2" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis2"/>
        <origin xyz="0.2575 -0.478 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c2" type="revolute">
        <parent link="verticalaxis2"/>
        <child link="connector2"/>
        <origin xyz="0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w2" type="continuous">
        <parent link="connector2"/>
        <child link="wheel2"/>
        <origin xyz="0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>


    <joint name="joint_p-a3" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis3"/>
        <origin xyz="0.2575 0 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c3" type="revolute">
        <parent link="verticalaxis3"/>
        <child link="connector3"/>
        <origin xyz="0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w3" type="continuous">
        <parent link="connector3"/>
        <child link="wheel3"/>
        <origin xyz="0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>


    <joint name="joint_p-a4" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis4"/>
        <origin xyz="-0.2575 0 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c4" type="revolute">
        <parent link="verticalaxis4"/>
        <child link="connector4"/>
        <origin xyz="-0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w4" type="continuous">
        <parent link="connector4"/>
        <child link="wheel4"/>
        <origin xyz="-0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>


    <joint name="joint_p-a5" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis5"/>
        <origin xyz="-0.2575 -0.478 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c5" type="revolute">
        <parent link="verticalaxis5"/>
        <child link="connector5"/>
        <origin xyz="-0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w5" type="continuous">
        <parent link="connector5"/>
        <child link="wheel5"/>
        <origin xyz="-0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>


    <joint name="joint_p-a6" type="revolute">
        <parent link="platform"/>
        <child link="verticalaxis6"/>
        <origin xyz="-0.2575 0.478 0"/>
        <axis xyz="0 0 1"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_a-c6" type="revolute">
        <parent link="verticalaxis6"/>
        <child link="connector6"/>
        <origin xyz="-0.0365 0 -0.220"/>
        <axis xyz="1 0 0"/>
        <limit lower="-3.14" upper="3.14" effort="30" velocity="1.0"/>
    </joint>
    <joint name="joint_c-w6" type="continuous">
        <parent link="connector6"/>
        <child link="wheel6"/>
        <origin xyz="-0.073 0 0"/>
        <axis xyz="1 0 0"/>
    </joint>




  <gazebo reference="platform">
    <material>Gazebo/Green</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel1">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel2">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel3">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel4">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel5">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>
  <gazebo reference="wheel6">
    <material>Gazebo/Blue</material>
    <turnGravityOff>true</turnGravityOff>
  </gazebo>


 <gazebo>
      <controller:gazebo_ros_time name="gazebo_ros_time" plugin="libgazebo_ros_time.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>100.0</updateRate>
        <interface:audio name="dummy_gazebo_ros_time_iface_should_not_be_here"/>
      </controller:gazebo_ros_time>


      <!-- PR2_ACTARRAY -->
      <controller:gazebo_ros_controller_manager name="gazebo_ros_controller_manager" plugin="libgazebo_ros_controller_manager.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>100.0</updateRate>
        <interface:audio name="gazebo_ros_controller_manager_dummy_iface" />
      </controller:gazebo_ros_controller_manager>


</gazebo>

</robot>