diff --git a/urdf/realsense.xacro b/urdf/realsense.xacro
index 12657398999e7485eb55c36c050c94c3d5a729ce..3cf0211926ea32b004b926b3bba7d5d89300febd 100644
--- a/urdf/realsense.xacro
+++ b/urdf/realsense.xacro
@@ -3,7 +3,7 @@
 <root xmlns:xacro="http://ros.org/wiki/xacro">
 
   <xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense.gazebo" />
-  <!--<xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>-->
+  <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
 
   <xacro:macro name="realsense_depth" params="parent model name:=camera *origin sim_config first:=true">
 
@@ -12,9 +12,9 @@
       <xacro:if value="${first == 'true'}">
         <xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro"/>
       </xacro:if>
-      <sensor_d435 parent="${parent}" name="${name}" use_nominal_extrinsics="$(arg use_nominal_extrinsics)">
+      <xacro:sensor_d435 parent="${parent}" name="${name}" use_nominal_extrinsics="$(arg use_nominal_extrinsics)">
         <xacro:insert_block name="origin"/>
-      </sensor_d435>
+      </xacro:sensor_d435>
     </xacro:if>
 
     <xacro:if value="${model == 'r410'}">