Exercise 2.0 - No transform from [root-link] to [base-link]

I tried to implement a root-link along with the base link and the roll_M1_link. Initially I wanted to make a floating joint between the root-link (fixed to the world) and the base-link (could move around if required) but apparently it is not supported.
Even when rviz converted the ‘floating joint’ into a ‘fixed joint’, I get the error under ‘RobotModel’: “No transform from [root_link] to [base_link]”.
How can I resolve this?

Edit: I cannot even select the [root link] as my Fixed-frame

<?xml version="1.0"?>

<robot name="mira">

   <!--Material Descriptions-->

   <gazebo reference="base_link">

       <kp>100000.0</kp>

       <kd>100000.0</kd>

       <mu1>10.0</mu1>

       <mu2>10.0</mu2>

       <material>Gazebo/Grey</material>

   </gazebo>

   <gazebo reference="roll_M1_link">

       <kp>100000.0</kp>

       <kd>100000.0</kd>

       <mu1>10.0</mu1>

       <mu2>10.0</mu2>

       <material>Gazebo/White</material>

   </gazebo>

   <!-- * * * Link Definitions * * * -->

   <link name="root_link">

       <visual>

           <origin rpy="0 0 0" xyz="0 0 0"/>

           <geometry>

               <box size="0.1 0.1 0.01"/>

           </geometry>

       </visual>

   </link>

   <link name="base_link">

       <inertial>

           <origin xyz="0 0 0" rpy="0 0 0"/>

           <mass value="0.18" />

           <inertia 

               ixx="0.0002835" ixy="0.0" ixz="0.0" 

               iyy="0.0002835" iyz="0.0" 

               izz="0.000324"/>

       </inertial>

       <collision>

           <origin xyz="0 0 0" rpy="0 0 0"/>

           <geometry>

               <cylinder radius="0.06" length="0.09"/>

           </geometry>

       </collision>

       <visual>

           <origin rpy="0 0 0" xyz="0 0 0"/>

           <geometry>

               <cylinder radius="0.06" length="0.09"/>

               <!--mesh filename="package://my_mira_description/models/mira/meshes/mira_body_v3.dae"/-->

           </geometry>

       </visual>

   </link>

   

   <link name="roll_M1_link">

       <inertial>

           <origin xyz="0 0 0" rpy="0 0 0"/>

           <mass value="0.01" />

           <inertia 

               ixx="0.0000000270833" ixy="0.0" ixz="0.0" 

               iyy="0.0000000270833" iyz="0.0" 

               izz="0.00000005"/>

       </inertial>

       <visual>

           <origin rpy="0 0 0" xyz="0 0 0"/>

           <geometry>

               <cylinder radius="0.01" length="0.005"/>

           </geometry>

       </visual>

   </link>

   

   <!--Joint Descriptions-->

   <joint name="free_joint" type="floating">

       <parent link="root_link"/>

       <child link="base_link"/>

       <origin xyz="0 0 0" rpy="0 0 0"/>

   </joint>

   <joint name="roll_joint" type="revolute">

       <parent link="base_link"/>

       <child link="roll_M1_link"/>

       <origin xyz="0 0 0" rpy="0 0 0"/>

       <limit lower="-0.2" upper="0.2" effort="0.1" velocity="0.005"/>

       <axis xyz="1 0 0"/>

   </joint>

   

</robot>

Hi,

I’ve tested the code and if you set it to fixed it works, perfectly.
Floating joints never have worked i Gazebo I’m afraid. Normally for ploating joints, we use primatic joints conected one to another ( but this also messed with fisics). If you want a floating element, the best way is to remove gravity form the model and create a floating robot control with forces. Otherwise I don’t know where you would want a floating joint, if so please tell us.

This is the code working with fixed joiunt:

<?xml version="1.0"?>
   <kp>100000.0</kp>

   <kd>100000.0</kd>

   <mu1>10.0</mu1>

   <mu2>10.0</mu2>

   <material>Gazebo/Grey</material>
   <kp>100000.0</kp>

   <kd>100000.0</kd>

   <mu1>10.0</mu1>

   <mu2>10.0</mu2>

   <material>Gazebo/White</material>
   <visual>

       <origin rpy="0 0 0" xyz="0 0 0"/>

       <geometry>

           <box size="0.1 0.1 0.01"/>

       </geometry>

   </visual>
   <inertial>

       <origin xyz="0 0 0" rpy="0 0 0"/>

       <mass value="0.18" />

       <inertia 

           ixx="0.0002835" ixy="0.0" ixz="0.0" 

           iyy="0.0002835" iyz="0.0" 

           izz="0.000324"/>

   </inertial>

   <collision>

       <origin xyz="0 0 0" rpy="0 0 0"/>

       <geometry>

           <cylinder radius="0.06" length="0.09"/>

       </geometry>

   </collision>

   <visual>

       <origin rpy="0 0 0" xyz="0 0 0"/>

       <geometry>

           <cylinder radius="0.06" length="0.09"/>

           <!--mesh filename="package://my_mira_description/models/mira/meshes/mira_body_v3.dae"/-->

       </geometry>

   </visual>
   <inertial>

       <origin xyz="0 0 0" rpy="0 0 0"/>

       <mass value="0.01" />

       <inertia 

           ixx="0.0000000270833" ixy="0.0" ixz="0.0" 

           iyy="0.0000000270833" iyz="0.0" 

           izz="0.00000005"/>

   </inertial>

   <visual>

       <origin rpy="0 0 0" xyz="0 0 0"/>

       <geometry>

           <cylinder radius="0.01" length="0.005"/>

       </geometry>

   </visual>
<joint name="free_joint" type="fixed">

   <parent link="root_link"/>

   <child link="base_link"/>

   <origin xyz="0 0 0" rpy="0 0 0"/>
   <parent link="base_link"/>

   <child link="roll_M1_link"/>

   <origin xyz="0 0 0" rpy="0 0 0"/>

   <limit lower="-0.2" upper="0.2" effort="0.1" velocity="0.005"/>

   <axis xyz="1 0 0"/>