diff --git a/config/ana_pan_tilt_xacro.yaml b/config/ana_pan_tilt_xacro.yaml
index 82c81930c8b168f6484e4a836df6bf876b42c190..b007208f351f4db235f0ee73dc9252cdfe8ad5f3 100644
--- a/config/ana_pan_tilt_xacro.yaml
+++ b/config/ana_pan_tilt_xacro.yaml
@@ -1,5 +1,5 @@
 pan_joint_name: pan
 tilt_joint_name: tilt
-load_name: camera_base_frame
+load_name: realsense_support_pan_tilt
 joint_interface: EffortJointInterface
 
diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro
index cdbe69c9021ea937e38c8a4ba210f0355e34f92d..3491d9192508dedb42deefc2d8302fbdbc01b984 100644
--- a/urdf/include/sensors.xacro
+++ b/urdf/include/sensors.xacro
@@ -2,7 +2,8 @@
 
 <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:include filename="$(find iri_realsense_depth_description)/urdf/realsense.xacro" />-->
+  <xacro:include filename="$(find iri_realsense_depth_description)/urdf/realsense_d435.xacro" />
   <xacro:include filename="$(find iri_bno055_imu_description)/urdf/bno055_imu.xacro" />
   <xacro:include filename="$(find iri_dynamixel_pan_tilt_description)/urdf/pan_tilt.xacro" />
 
@@ -59,47 +60,28 @@
       <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">
+    <!--<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.26 0" />
-    </xacro:realsense_depth>
+    </xacro:realsense_depth>-->
+
+    <xacro:realsense_d435_depth parent="${name}_realsense_support" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_config.yaml">
+      <origin xyz="0.0 0.0 0.0265" rpy="0 0.26 0" />
+    </xacro:realsense_d435_depth>
 
     <xacro:bno055_imu name="imu" parent="base_footprint" resolution="low_res" sim_config="$(find iri_ana_gazebo)/config/ana_bno055_config.yaml">
       <origin xyz="0.11928 -0.08805 0.23061" rpy="0 -1.5707 0" />
     </xacro:bno055_imu>
 
     <link name="${pan_tilt_xacro_properties['load_name']}">
-      <visual>
-        <geometry>
-          <box size=".05 .05 .01"/>
-        </geometry>
-        <origin rpy="0 ${pi/2} 0" xyz="0 0 .025"/>
-        <material name="blue">
-          <color rgba="0 0 .8 1"/>
-        </material>
-      </visual>
-      <inertial>
-        <origin rpy="0 ${pi/2} 0" xyz="0 0 .025"/>
-        <mass value="1"/>
-        <inertia 
-          ixx="0.0001" ixy="0.0" ixz="0.0" 
-          iyy="0.0001" iyz="0.0" 
-          izz="0.0001"/>
-      </inertial>
     </link>
 
-    <link name="camera_optical_frame"/>
+    <!--<xacro:realsense_depth parent="${pan_tilt_xacro_properties['load_name']}" model="d435" name="camera_pan_tilt" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_pan_tilt_config.yaml" first="false">
+      <origin xyz="0.0 0.04 -0.016" rpy="-${pi/2} 0 ${pi}" />
+    </xacro:realsense_depth>-->
 
-    <gazebo reference="${pan_tilt_xacro_properties['load_name']}">
-      <mu1>0.2</mu1>
-      <mu2>0.2</mu2>
-      <material>Gazebo/Blue</material>
-    </gazebo>
-
-    <joint name="${pan_tilt_xacro_properties['load_name']}_to_camera_optical_frame" type="fixed" >
-      <parent link="${pan_tilt_xacro_properties['load_name']}"/>
-      <child link="camera_optical_frame"/>
-      <origin xyz="0.0 0.0 0.025" rpy="${pi/2} 0 -${pi/2}"/>
-    </joint>
+    <xacro:realsense_d435_depth parent="${pan_tilt_xacro_properties['load_name']}" name="camera_pan_tilt" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_pan_tilt_config.yaml">
+      <origin xyz="0.0 0.04 -0.016" rpy="-${pi/2} 0 ${pi}" />
+    </xacro:realsense_d435_depth>
 
     <xacro:pan_tilt parent="${name}_box" pan_joint_name="${pan_tilt_xacro_properties['pan_joint_name']}" tilt_joint_name="${pan_tilt_xacro_properties['tilt_joint_name']}" load_name="${pan_tilt_xacro_properties['load_name']}" joint_interface="${pan_tilt_xacro_properties['joint_interface']}" sim_config="$(find iri_ana_gazebo)/config/ana_pan_tilt_gazebo.yaml">
       <origin xyz="0.15 0.0 0.2" rpy="0 0 0" />