ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Loading URDF file into gazebo

asked 2018-11-14 15:38:25 -0500

guilt11 gravatar image

updated 2018-11-14 15:41:40 -0500

gvdhoorn gravatar image

I recently download a URDF file, the link is https://github.com/UMich-BipedLab/Cas... , I would like to simulate this model inside the gazebo and apply the PID control on the joints, so the first step I done is to using roslaunch on the URDF file to simulate the model on the gazebo, the launch file shown below:

<launch>

  <!-- these are the arguments you can pass this launch file, for example paused:=true -->
  <arg name="paused" default="false"/>
  <arg name="use_sim_time" default="true"/>
  <arg name="gui" default="true"/>
  <arg name="headless" default="false"/>
  <arg name="debug" default="false"/>

  <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find cassie_gazebo)/worlds/cassie.world"/>
    <arg name="debug" value="$(arg debug)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="paused" value="$(arg paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="headless" value="$(arg headless)"/>
  </include>

  <!-- Load the URDF into the ROS Parameter Server -->
<param name="cassie_description" textfile="$(find cassie_description)/urdf/cassie.urdf"/>

  <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
args="-urdf -param cassie_description -model cassie" />


  <!-- ros_control rrbot launch file -->
  <!--include file="$(find rrbot_control)/launch/rrbot_control.launch" /-->

</launch>

The launching is successful, the model appear on the left control panel, however there is only one link which is pelvis appeared on the list, other links does not show on the list.

I also use the following command to verify if the launch file is wrong, this work perfectly fine for other model, and the same problem appear with the following command:

rosrun gazebo_ros spawn_model -file `rospack find cassie_description`/urdf/cassie.urdf -urdf -z 1 -model cassie

I would be really appreciated for anyone who could solve this problem.

edit retag flag offensive close merge delete

Comments

Does adding this in the cassie.urdf produces a different result ?

  <link name="world"/>

  <joint name="fixed" type="fixed">
    <parent link="world"/>
    <child link="pelvis"/>
  </joint>

It's just to check if the urdf is correct but that won't totally solve your issue.

Delb gravatar image Delb  ( 2018-11-15 02:15:18 -0500 )edit

I really appreciate your help, the expert below already answered the questions clearly, thank you very much :)

guilt11 gravatar image guilt11  ( 2018-11-15 13:31:34 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-11-15 11:24:33 -0500

RDaneelOlivaw gravatar image

Hi.

I created this launch ROS package to spawn at least a working version of Cassie robot. The only thing remaining is to calibrate the PIDs and the joint limits.

I had to make some modifications to the original cassie.xacro in cassie_description package because it was only for RVIZ purposes, not useful for Gazebo simulation. There fore you have to add collisions, masses some inertias. You have to also add the Gazebo Physics elements like mu,kp or the material. I had also to correct some elements of the transimissions that weren't quite right in the xacro at least.

As I said the solution is just to have it in Gazebo, because the PID calibration is loads of work and I dont have access to the real robot to compare the fidelity of the performance and speed. Thats work you will have to do.

image description

Example:

<xacro:macro name="vectorNav">
<link name="vectorNav">
  <inertial>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <mass value="0.01" />
        <inertia ixx="1.66666666667e-07" ixy="0.0" ixz="0.0" iyy="1.66666666667e-07" iyz="0.0" izz="1.66666666667e-07"/>
    </inertial>
    <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <box size="0.01 0.01 0.01"/>
        </geometry>
    </collision>
    <visual>
        <origin rpy="0.0 0 0" xyz="0 0 0"/>
        <geometry>
            <box size="0.1 0.1 0.1"/>
        </geometry>
    </visual>
</link>

  <gazebo reference="vectorNav">
<kp>100000000.0</kp>
<kd>10.0</kd>
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>10.0</maxVel>
<minDepth>0.0005</minDepth>
<material>Gazebo/Green</material>

</gazebo> </xacro:macro>

Because ROS Anwsers doesnt allow me to upload non image files I'll have to give you the git where I uploaded all the code. Here you have the corrected xacro ready for moving it and all the code related to it in a convenient git: Git with XACRO and spawn and control

I have also created a ROSJect with all the project ready to go.

I've also created a tiny video to explain other details of the solution

Hope it helped

edit flag offensive delete link more

Comments

Oh my god, you are the real expert ! enjoy your coding and tutorial, really appreciate your help :)

guilt11 gravatar image guilt11  ( 2018-11-15 13:29:28 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-11-14 15:38:25 -0500

Seen: 2,411 times

Last updated: Nov 15 '18