Unable to open CAD files in gazebo

I have a pipe.obj and pipe.stl which can be opened in any CAD software(for eg. freecad). But when I try to open that in Gazebo Garden, the pipe.obj shows up as a solid cylinder instead of a hollow one where as the pipe.stl is not seen in the simulation itself although it shows up in the entity tree.

The CAD files is available here

My sdf is

<?xml version="1.0" ?>
<sdf version="1.9">
    <world name="map">
        <physics name="1ms" type="ignore">
            <max_step_size>0.001</max_step_size>
            <real_time_factor>1.0</real_time_factor>
        </physics>

        <plugin filename="gz-sim-physics-system"
                name="gz::sim::systems::Physics">
        </plugin>
        <plugin filename="gz-sim-sensors-system"
                name="gz::sim::systems::Sensors">
            <render_engine>ogre2</render_engine>
        </plugin>
        <plugin filename="gz-sim-user-commands-system"
                name="gz::sim::systems::UserCommands">
        </plugin>
        <plugin filename="gz-sim-scene-broadcaster-system"
                name="gz::sim::systems::SceneBroadcaster">
        </plugin>
        <plugin filename="gz-sim-imu-system"
                name="gz::sim::systems::Imu">
        </plugin>

            <!-- Moving Forward-->
        <plugin filename="gz-sim-triggered-publisher-system"
                name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Int32" topic="/keyboard/keypress">
            <match field="data">16777235</match>
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.2}, angular: {z: 0.0}
        </output>
        </plugin>

        <!-- Moving Backward-->
        <plugin filename="gz-sim-triggered-publisher-system"
                name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Int32" topic="/keyboard/keypress">
            <match field="data">16777237</match>
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: -0.2}, angular: {z: 0.0}
        </output>
        </plugin>

        <!-- Moving Right-->
        <plugin filename="gz-sim-triggered-publisher-system"
                name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Int32" topic="/keyboard/keypress">
            <match field="data">16777236</match>
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.2}, angular: {z: -0.2}
        </output>
        </plugin>

        <!-- Moving Left-->
        <plugin filename="gz-sim-triggered-publisher-system"
                name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Int32" topic="/keyboard/keypress">
            <match field="data">16777234</match>
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.2}, angular: {z: 0.2}
        </output>
        </plugin>

            <!-- Stop Moving -->
        <plugin filename="gz-sim-triggered-publisher-system"
                name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Int32" topic="/keyboard/keypress">
            <match field="data">48</match>   <!-- 0 -->
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {y: -0.5}, angular: {z: 0.0}
        </output>
        </plugin>
       
        <scene>
            <ambient>1.0 1.0 1.0</ambient>
            <background>0.8 0.8 0.8</background>
            <sky></sky>
        </scene>

        <light type="directional" name="sun">
            <cast_shadows>true</cast_shadows>
            <pose>0 0 10 0 0 0</pose>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
            <attenuation>
                <range>1000</range>
                <constant>0.9</constant>
                <linear>0.01</linear>
                <quadratic>0.001</quadratic>
            </attenuation>
            <direction>-0.5 0.1 -0.9</direction>
        </light>

        <spherical_coordinates>
            <latitude_deg>-35.3632621</latitude_deg>
            <longitude_deg>149.1652374</longitude_deg>
            <elevation>10.0</elevation>
            <heading_deg>0</heading_deg>
            <surface_model>EARTH_WGS84</surface_model>
        </spherical_coordinates>

        <model name="floor">
            <static>true</static>
            <link name="link">
                <collision name="collision">
                    <geometry>
                        <plane>
                            <normal>0 0 1</normal>
                            <size>100 100</size>
                        </plane>
                    </geometry>
                    <surface>
                        <friction>
                            <ode>
                                <mu>100</mu>
                                <mu2>50</mu2>
                            </ode>
                        </friction>
                    </surface>
                </collision>
                <visual name="visual">
                    <cast_shadows>false</cast_shadows>
                    <geometry>
                        <plane>
                            <normal>0 0 1</normal>
                            <size>100 100</size>
                        </plane>
                    </geometry>
                    <material>
                        <diffuse>0.8 0.3 0.3 1</diffuse>
                    </material>
                </visual>
            </link>
        </model>
        
        <model name="pipe">
            <pose>0 50 -20 0 0 1.57</pose>
   <static>true</static>
   <link name="link">
     <collision name="collision">
       <geometry>
         <mesh>
           <uri>model://pipe/pipe.stl</uri>
           <scale> 1 1 1 </scale>
         </mesh>
       </geometry>
     </collision>
     <visual name="visual">
       <material>
         <ambient>0.8 0.7 0.5 1</ambient>
         <diffuse>0.6 0.3 0.5 1</diffuse>
         <specular>0.2 0.7 0.8 1</specular>
         <emissive>0 0 0 1</emissive>
       </material>
       <geometry>
         <mesh>
           <uri>model://pipe/pipe.stl</uri>
           <scale> 1 1 1 </scale>
         </mesh>
       </geometry>
     </visual>
   </link>
 </model>


    </world>
</sdf>

Any thoughts please?

Thanks

I would check orientation of normals in the exported files.