Robotics StackExchange | Archived questions

ball falling through ground instead of laying on ground plane

This should be easy, but I'm missing something obvious.

I'm trying to create a urdf file for a ball that that I can launch multiple times at different locations through roslaunch.

<node name="ball_1" pkg="gazebo_ros" type="spawn_model" args="-file $(find my_model/urdf/ball.urdf -urdf -x -1.2192 -y 2.56032 -z 0.0254 -s 0.0254 -c "green" -model ball_1" />

My attempt at urdf is :

image description

I first tried without the gazebo tag, but in either case the ball gets added to the gazebo simulation, but then it is not visible . I can select the model "ball_1" in Gazebo, but the pose continues to go negative as if it fell through the ground plane.

The robot model is working as expected.

I'm running ROS jade under Ubuntu 14.04 with a separate gazebo5 install

Asked by dcconner on 2016-04-13 16:48:49 UTC

Comments

Have you figured out what the problem was? If so, can you please submit it as an answer? I'm facing the same thing.

Asked by janindu on 2017-05-07 01:00:15 UTC

Hey, even I am facing the same issue. Let me know the solution if anyone of you have figured out

Asked by Sam6 on 2017-07-21 12:24:00 UTC

Answers

I'm using the following:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:macro name="simple_ball" params="id:=red mass:=0.25 radius:=0.0254 gazebo_color:=Red ">

      <link name="${id}_ball">
        <inertial>
            <mass value="${mass}" />
            <origin xyz="0 0 0" />
            <inertia  ixx="${radius*radius*mass*2./5.}" ixy="0.0"  ixz="0.0"  iyy="${radius*radius*mass*2./5.}"  iyz="0.0"  izz="${radius*radius*mass*2./5.}" />
        </inertial>
        <visual>
          <origin xyz="0 0 0" rpy="0 0 0" />
          <geometry>
            <sphere radius="${radius}"/>
          </geometry>
        </visual>
        <collision>
          <origin xyz="0 0 0" rpy="0 0 0" />
          <geometry>
            <sphere radius="${radius}"/>
          </geometry>
        </collision>
      </link>
      <gazebo reference="${id}_ball">
          <mu>100000</mu>
          <mu2>100000</mu2>
          <material>Gazebo/${gazebo_color}</material>
          <turnGravityOff>false</turnGravityOff>
      </gazebo>

  </xacro:macro>
</robot>

with setting a particular size color:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:include filename="$(find chris_world_models)/urdf/simple_ball.urdf.xacro"/>

  <simple_ball id="red" mass="0.25" radius="0.0254" gazebo_color="Red"/>

</robot>

and launch:

<launch>
  <arg name="ball_id" default="ball0" />
  <arg name="color"   default="red"/>
  <arg name="x_pos"   default="-1.0"/>
  <arg name="y_pos"   default="-1.0"/>
  <arg name="z_pos"   default= "0.05"/> <!-- slight drop for small ball -->

  <!-- make sure all colors are available -->
  <param name="red_ball"   command="$(find xacro)/xacro -v --inorder $(find chris_world_models)/urdf/red_ball.urdf.xacro" />
  <param name="green_ball" command="$(find xacro)/xacro -v --inorder $(find chris_world_models)/urdf/green_ball.urdf.xacro" />
  <param name="blue_ball"  command="$(find xacro)/xacro -v --inorder $(find chris_world_models)/urdf/blue_ball.urdf.xacro" />

  <!-- add ball of specified color and id to the gazebo simlation at the given coordinates -->
  <node name="$(arg ball_id)" pkg="gazebo_ros" type="spawn_model" args="-param $(arg color)_ball  -urdf -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -model $(arg ball_id)" />

</launch>

Full setup at: https://github.com/CNURobotics/chris_world_models

Asked by dcconner on 2017-10-28 11:16:44 UTC

Comments

I believe you always have to define inertial of the model for the physics engine to be able to compute its interactions with other objects. So just add the

<inertial>
    <mass value="1" />
    <inertia  ixx="0.001" ixy="0.0"  ixz="0.0"  
              iyy="0.001"  iyz="0.0"  
              izz="0.001" /> 
</inertial>

section into the model's urdf file (and compute proper inertial matrix).

Asked by kumpakri on 2018-10-03 03:02:48 UTC

Comments