Home | Tutorials | Wiki | Issues
Ask Your Question
0

How to specify URDF link which attaches to world ground?

asked 2020-02-09 12:14:26 -0600

TorontoRoboticsClub gravatar image

updated 2020-02-09 12:40:33 -0600

Hello. The system is Gazebo7 (ver 7.16), running ROS Kinetic, in Ubuntu 16.04. The model I am working with looks like so:

image description

The problem is that when I start the simulation my robot jumps up like crazy (13 meters or so) and lands painfully. I was able to figure out that the jump occurs due to the fact that the simulation starts with the robot partially "inside" the ground:

image description

I now understand that the reason for this is that my base_link (the largest box in the center of the robot) which is the coordinate system origin of my model is snapped to the ground of the simulation (figured this out using: https://answers.ros.org/question/2251...). The problem is that the base_link is not the lowest part of the model.

I tried moving the Z axis of the <origin> tag of the base_link in the URDF file, but it didn't have the desired effect:

image description

Is there a tag I can integrate into my URDF that dictates which link snaps to the ground? or is there a mod I can do in the .world file? I am hoping the simulation can be started with the wheels on the ground rather than inside the ground.

Last piece of information: I saved the world with the robot on all four wheels, and when I launch the simulation all is well; however as soon as I select "Reset world" from the "Edit" menu, the robot jumps super high.

I have attached the URDF for the base_link for reference:

<link name="base_link">
    <!--If you do not explicitly specify a <collision> element. Gazebo will 
  treat your link as "invisible" to laser scanners and collision checking-->
<collision>
  <geometry>
    <box size="0.65 0.381 0.132"/>
  </geometry>
  <!-- line below allows us to insert:<origin rpy="${rpy}" xyz="${xyz}"/>-->
  <origin rpy="0 0 0" xyz="-0.325 -0.1905 0.066"/>
</collision>
<visual>
  <geometry>
    <!--box dimensions is Meters. L X W X H where the L X H is a ractange, 
          and the H extrudes it upwards -->
    <box size="0.65 0.381 0.132"/>
  </geometry>
  <!-- line below allows us to insert:<origin rpy="${rpy}" xyz="${xyz}"/>-->
  <origin rpy="0 0 0" xyz="-0.325 -0.1905 0.066"/>
  <material name="white"/>
</visual>
<inertial>
  <!-- line below allows us to insert:<origin rpy="${rpy}" xyz="${xyz}"/>-->
  <origin rpy="0 0 0" xyz="-0.325 -0.1905 0.066"/>
  <!--all blocks now need a 'mass' argument-->
  <mass value="25"/>
  <!--This is the 3x3 inertial matrix. See: https://wiki.ros.org/urdf/XML/link -->
  <!--where x=length; y=width; z=height. these lines of code came from 
    Emiliano Borghi's project-->
  <inertia ixx="0.33871875" ixy="0" ixz="0" iyy="0.916508333333" iyz="0" izz="0.916508333333"/>
</inertial>
</link>

Thanks in advance.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2020-02-10 07:27:12 -0600

kumpakri gravatar image

If I understand correctly you don't actually want to attach the robot to the ground, right? You want to spawn the robot above the ground and you want the robot to move freely with the respect to the ground. Correct?

How do you launch the simulation? Where does your robot spawning happens? Since you showed us the robot description in URDF, I suppose you use the launch files that look something like this.

<?xml version="1.0"?>
<launch>
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="debug" default="false" />
    <arg name="verbose" default="true" />

    <param name="world" value="$(arg world)" />

    <!-- startup simulated WORLD -->
    <include file="$(find robot_gazebo)/launch/world.launch">
        <!--<arg name="world" value="$(arg world)"/>-->
        <arg name="paused" value="$(arg paused)" />
        <arg name="use_sim_time" value="$(arg use_sim_time)" />
        <arg name="gui" value="$(arg gui)" />
        <arg name="debug" value="$(arg debug)" />
        <arg name="verbose" value="$(arg verbose)" />
    </include>

    <param name="robot_description"
        command="$(find xacro)/xacro --inorder '$(find robot_gazebo)/launch/upload_robot.xacro' " />

    <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model myrobot -param robot_description "/>

    <!-- ros_control robot_control launch file -->
    <!-- creates topics for joints state and joint controller -->
    <include file="$(find robot_control)/launch/myrobot_control.launch" />

</launch>

If that is correct, find the line where you call the spawn_model node. Where you input the arguments for the node, for example name of your robot and its description, you can also specify the pose of your robot. So the x, y and z coordinates in the world and the orientation R (roll), P (pitch) and Y (yaw). See the example below.

<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
    args="-urdf -model myrobot -param robot_description -x 0 -y 0 -z 0.5 - R 0 -P 0 -Y 0"/>
edit flag offensive delete link more

Comments

@kumpakri Not only did you figure out all my code correctly, but you even got the indentation right!!! Thanks a ton!!! with your solution I don't need to mess around with the URDF. It's a very clean solution. Thanks again!!!

TorontoRoboticsClub gravatar imageTorontoRoboticsClub ( 2020-02-10 16:46:31 -0600 )edit
0

answered 2020-02-09 15:38:25 -0600

nlamprian gravatar image

There is no snapping of any link to the ground. A model sits on the ground based on its collision geometries. So, if the wheels, for example, do not have any collision geometries, they are gonna go through the ground.

Suggestions:

  1. Add a base_footprint link which is on the ground level, below base_link. This way you'll make sure that the robot is not spawned half-way through the ground, and thus you don't have any explosion
  2. Then, click to View > Collisions in the gazebo client to visualize the collision geometries, and understand what is wrong with your model

I hope this helps

edit flag offensive delete link more

Comments

@nlamprian thanks for your help... Much appreciated! I looked at the collisions as you suggested and it was cool to learn about this feature. Thanks again.

TorontoRoboticsClub gravatar imageTorontoRoboticsClub ( 2020-02-10 16:48:30 -0600 )edit
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2020-02-09 12:14:26 -0600

Seen: 48 times

Last updated: Feb 10