Xacro is not properly launched in Gazebo: missing link
Hi I am trying to simplify my model using xacro. My idea is to have a macro:xacro for all the truck wheels. At this moment I am just trying to create the first shaft front left wheel using xacro. The good news is that the left wheel link and the left wheel joint are created and visualized in Rviz!
However in Gazebo the wheel and joint do not appear. I am going to share my urdf.xacro here as well as the launch files.
The urdf:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="iaz_truck">
<xacro:property name="tire_rad" value="2" />
<xacro:property name="tire_len" value="6" />
<link name="dummy">
</link>
<link name="base_link">
<inertial>
<mass value="1"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<link
name="chassis_link">
<inertial>
<origin
xyz="-2.6 5.5 -2.375"
rpy="0 0 0" />
<mass
value="706.504582027022" />
<inertia
ixx="39.450737574524"
ixy="-0.0360220237393506"
ixz="0.0791219230947013"
iyy="53.8198880289704"
iyz="-1.15911466511096"
izz="40.3544359429485" />
</inertial>
<visual>
<origin
xyz="-2.6 5.5 -2.375"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://urdf_chassis_pkg/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
</material>
</visual>
<collision>
<origin
xyz="-2.6 5.5 -2.375"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://urdf_chassis_pkg/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<joint name="dummy_joint" type="fixed">
<parent link="dummy"/>
<child link="base_link"/>
</joint>
<joint name="base_link_connection" type="fixed">
<parent link = "base_link"/>
<child link= "chassis_link"/>
<origin xyz="2 0 0.5" rpy= "0 0 1.57"/>
<axis xyz="1 0 0"/>
</joint>
<!-- Front link -->
<link name = "front_link">
<inertial>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<mass
value="20" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<box size = "0.05 2.5 0.05 "/>
</geometry>
<material
name="">
<color rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<box size = "0.1 2.0 0.1 "/>
</geometry>
</collision>
</link>
<!-- Connection Chassis_Link to Front link -->
<joint name="front_joint" type="fixed">
<parent link="chassis_link"/>
<child link="front_link"/>
<origin rpy="0 0 1.57079632679" xyz="-0.1 -3.6 0.030"/>
</joint>
<!--Steer Link : Link to connect Front Link and Ackermann Bar -->
<link name="steer_link">
<inertial>
<mass value="5.0"/>
<origin xyz="0 0 0 ...