From a773dc9f616aa908babba9b7f74fea3a57f9dfce Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Thu, 25 Oct 2018 17:21:10 +0200
Subject: [PATCH] Chnaged the position of the sensors on the urdf file to match
 their real position.   * Velodyne rotated 180 degrees   * Realsense pitch set
 to 0.26 radians.

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

diff --git a/urdf/sensors.xacro b/urdf/sensors.xacro
index 6e2fe0d..b23e16f 100644
--- a/urdf/sensors.xacro
+++ b/urdf/sensors.xacro
@@ -39,7 +39,7 @@
     </joint>
 
     <xacro:velodyne_vlp16 name="velodyne" parent="${parent}" resolution="high_res" sim_config="$(find iri_ana_gazebo)/config/ana_velodyne_config.yaml">
-      <origin xyz="0.0 0.0 0.1" rpy="0 0 0" />
+      <origin xyz="0.0 0.0 0.1" rpy="0 0 3.14159" />
     </xacro:velodyne_vlp16>
 
     <link name="${name}_realsense_support">
@@ -52,7 +52,7 @@
     </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" />
+      <origin xyz="0.0 0.0 0.0265" rpy="0 0.26 0" />
     </xacro:realsense_depth>
 
     <xacro:bno055_imu name="imu" parent="base_footprint" resolution="low_res" sim_config="$(find iri_ana_gazebo)/config/ana_bno055_config.yaml">
-- 
GitLab