diff --git a/urdf/sensors.xacro b/urdf/sensors.xacro
index b8f00065c92d3846c69bca4c989b049946de3db0..05a11b322e42d3ba8e9bbe6dc151feed38313c30 100644
--- a/urdf/sensors.xacro
+++ b/urdf/sensors.xacro
@@ -2,11 +2,11 @@
 
 <root xmlns:xacro="http://ros.org/wiki/xacro">
   <xacro:include filename="$(find iri_velodyne_lidar_description)/urdf/velodyne_vlp16.xacro" />
+  <xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense.xacro" />
 
   <xacro:macro name="sensors" params="name parent *origin">
-
    
-    <link name="box">
+    <link name="${name}_box">
       <inertial>
         <mass value="4.00000000" />
         <origin xyz="-0.02349208 0.00000000 0.20998619" rpy="0 0 0"/>
@@ -33,14 +33,9 @@
       </collision>
     </link>
     
-    <gazebo reference="box">
-      <material>Gazebo/Grey</material>
-    </gazebo>
-
-
-    <joint name="joint_${parent}_to_box" type="fixed" >
+    <joint name="joint_${parent}_to_${name}_box" type="fixed" >
       <parent link="${parent}"/>
-      <child link="box"/>
+      <child link="${name}_box"/>
       <origin xyz="0 0 0.3" rpy="0 0 0"/>
     </joint>
 
@@ -48,6 +43,19 @@
       <origin xyz="0.0 0.0 0.1" rpy="0 0 0" />
     </xacro:velodyne_vlp16>
 
+    <link name="${name}_realsense_support">
+    </link>
+
+    <joint name="joint_${parent}_to_${name}_realsense_support" type="fixed" >
+      <parent link="${parent}"/>
+      <child link="${name}_realsense_support"/>
+      <origin xyz="0.26374 0 -0.0485" rpy="0 0 0"/>
+    </joint>
+
+    <xacro:realsense_depth parent="${name}_realsense_support" model="d435" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_config.yaml">
+      <origin xyz="0.0 0.0 0.0265" rpy="0 0.52 0" />
+    </xacro:realsense_depth>
+
   </xacro:macro>
 
 </root>