From c737fe5d6744392ac3dd42b1f9bc8ae779a22eec Mon Sep 17 00:00:00 2001
From: fherrero <fherrero@iri.upc.edu>
Date: Wed, 9 Jun 2021 12:59:58 +0200
Subject: [PATCH] Remove second realsense sensor

---
 urdf/include/sensors.xacro | 17 ++---------------
 1 file changed, 2 insertions(+), 15 deletions(-)

diff --git a/urdf/include/sensors.xacro b/urdf/include/sensors.xacro
index 22897ac..27e452f 100644
--- a/urdf/include/sensors.xacro
+++ b/urdf/include/sensors.xacro
@@ -56,26 +56,13 @@
     <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_d435_depth parent="${name}_realsense_support" name="nav_cam" 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>
-
-    <link name="${name}_realsense_support_top">
-    </link>
-
-    <joint name="joint_${parent}_to_${name}_realsense_support_top" type="fixed" >
-      <parent link="${parent}"/>
-      <child link="${name}_realsense_support_top"/>
       <origin xyz="0.36 0 0.42" rpy="0 0 0"/>
     </joint>
 
-    <xacro:realsense_d435_depth parent="${name}_realsense_support_top" name="nav_cam_top" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_top_config.yaml">
+    <xacro:realsense_d435_depth parent="${name}_realsense_support" name="nav_cam" sim_config="$(find iri_ana_gazebo)/config/ana_realsense_config.yaml">
       <origin xyz="0.0 0.0 0.0265" rpy="0 1.0 0" />
     </xacro:realsense_d435_depth>
-    
+
     <xacro:bno055_imu name="imu_sim" 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 0 0" />
     </xacro:bno055_imu>
-- 
GitLab