Gazebo | Ignition | Community
Ask Your Question
0

Mobile Robot in gazebo using URDF files instead of SDF, the wheels are disappearing

asked 2016-10-28 01:37:43 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

Hello,

I am trying to create a mobile robot using urdf and following the tutorial "Gazebo : Tutorial : Make a Mobile Robot" that creates SDF file. In my case I changed the size of the robot and I am creating it using URDF. I did the following: 1- I created a file called mobileRobot.urdf.xacro

 <?xml version="1.0"?>
 <robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro"> 
 <xacro:include filename="$(find my_robot_description)/urdf/my_robot.gazebo" /> 
 <xacro:include filename="$(find my_robot_description)/urdf/my_robot.xacro" />
 </robot>

2- I created another file called my_robot.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"> 
<property name="pi" value="3.1415926535897931" />
<link name="base_link" >
<inertial>  <mass value="0.5"/>
<inertia ixx="0.005395" ixy="0.0" ixz="0.0" iyy="0.005395" iyz="0.0" izz ="0.007470"/>
</inertial>
<collision name="collision">
    <geometry>
    <box size="0.3 0.3 0.2" />
    </geometry>
  </collision>
  <visual name="visual">
     <geometry>
              <box size="0.3 0.3 0.2"/>
              <material name="blue"> </material>
    </geometry>
    </visual>
    </link>

   <link name="left_wheel">
      <collision>
  <origin xyz="0.0 0.18 -0.1" rpy="0 1.5707 1.5707" /> 
      <geometry>
            <cylinder radius=".1" length=".05"/>     
      </geometry>
    </collision>
    <visual>
<origin xyz="0.0 0.18 -0.1" rpy="0 1.5707 1.5707" /> 
      <geometry>
        <cylinder radius=".1" length=".05"/>
      </geometry>
    </visual>
  </link>


<link name="right_wheel">
    <collision>
<origin xyz="0.0 -0.18 -0.1" rpy="0 1.5707 1.5707" /> 
      <geometry>
        <cylinder radius=".1" length=".05"/>     
      </geometry>
    </collision>
    <visual>
<origin xyz="0.0 -0.18 -0.1" rpy="0 1.5707 1.5707" />
      <geometry>
        <cylinder radius=".1" length=".05"/>
      </geometry>
    </visual>
  </link>

<joint type="revolute" name="right_wheel_hinge">
    <limit effort="30" velocity="1.0" lower="-2.792526" upper="2.792526"/>
<origin xyz="0 0 0.03" rpy="0 0 0" /> 
    <child link="right_wheel"/>
    <parent link="base_link"/>
    <axis xyz="0 1 0"/>
    </joint>

<joint type="revolute" name="left_wheel_hinge">
    <!--<limit effort="30" velocity="1.0" lower="-2.792526" upper="2.792526"/>-->
<origin xyz="0 0 0.03" rpy="0 0 0" />
    <child link="left_wheel"/>
    <parent link="base_link"/>
    <dynamics damping="0.7"/>
    <axis xyz="0 1 0"/>
    </joint>

  </robot>

3- File my_robot.gazebo

  <?xml version="1.0"?>
  <robot>
  <!-- ros_control plugin -->
   <gazebo>
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/My_ROBOT</robotNamespace>
        </plugin>
   </gazebo>
   <!-- base_link -->
   <gazebo reference="base_link">
               <selfCollide>true</selfCollide>
               <gravity>true</gravity>
               <material>Gazebo/Blue</material>
     </gazebo>
   </robot>

Finally I created a launch file

    <?xml version='1.0'?>
    <launch>
<arg name="model" default="$(find my_robot_description)/robots/mobileRobot.urdf.xacro"/>
<param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />
<include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="use_sim_time" value="true"/></include>

<node name="Robot1" pkg="gazebo_ros" type="spawn_model"
    args="-x 2.0 -unpause -urdf -model robot1 -param robot_description" respawn="false" output="screen" />

<!--<node name="Robot2" pkg="gazebo_ros" type="spawn_model"
    args="-x 3.0 -unpause -urdf -model robot2 -param robot_description" respawn="false" output="screen" />
-->
<node pkg="robot_state_publisher" type="robot_state_publisher"  name="robot_state_publisher">
        <param name="publish_frequency" type="double" value="30.0" />
</node>
<node ...
(more)
edit retag flag offensive close merge delete

Comments

sorry, I'm too lazy to check it myself. Wheels are disappearing from where? the URDF or corresponding sdf file? or Gazebo?

eugene-katsevman gravatar imageeugene-katsevman ( 2017-04-11 10:08:11 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2018-07-10 07:09:59 -0500

rukn gravatar image

I think you have to give inertial values for the wheels too..

edit flag offensive delete link more
0

answered 2018-07-10 09:08:05 -0500

updated 2018-07-10 10:20:08 -0500

1) When I run the launch file I cant see the wheels of the robots in gazebo. but If I changed the wheels to type fixed I can see the wheels.

@rukn's answer is good.

  • Give your wheel realistic approximate inertial values. See: https://en.wikipedia.org/wiki/List_of...
  • Start gazebo in paused mode, then advance the simulation in single time steps. This will help you figure out what is causing the model to fly apart.

2) Also, what is the tag property to convert from <static> false </static> (this one in SDF) from SDF to xacro ?

Sorry, I don't understand what you are asking here. Please rephrase your question.


3) Moreover, if the size of the box mobile robot is 0.3 0.3 0.2 are the links (left and right wheels) and joint's position, visual and geometry I created for this size are acceptable ?

It depends on what you're trying to simulate and what you are using the simulation for. You want your simulation to match either a real robot or a planned robot as closely as possible.

  • If your focus is physical interactions, then it's important to get the collision elements right (link masses, inertial matrices, etc...).
  • Whereas if your focus is image processing/object recognition, then you can "fake" the physics - really you're faking the fake physics - but you'll need to have really good visual elements (colors, textures, meshes, etc...).

4) If I want to control this robot using keyboard, what should I do to make this robot publish and subscribe topics to connect it with ROS ?

You can:

edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2016-10-28 01:37:43 -0500

Seen: 2,656 times

Last updated: Jul 10 '18