From 62a39a8c8e6b60602187b7df3a94ef81bb089ddf Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Fri, 22 Jun 2018 10:13:16 +0200
Subject: [PATCH] Added all the parameters of the gazebo plugin to the YAML
 file.

---
 .../microstrain_3dm_gx3_imu_sim_config.yaml   | 28 +++++++++++++++++--
 urdf/imu.gazebo                               | 22 +++++++++------
 2 files changed, 38 insertions(+), 12 deletions(-)

diff --git a/config/microstrain_3dm_gx3_imu_sim_config.yaml b/config/microstrain_3dm_gx3_imu_sim_config.yaml
index 89986c0..6e81b87 100644
--- a/config/microstrain_3dm_gx3_imu_sim_config.yaml
+++ b/config/microstrain_3dm_gx3_imu_sim_config.yaml
@@ -1,3 +1,25 @@
-rate: 10.0
-namespace: '/prova'
-imu_topic: 'imu_raw'
+rate: 100.0
+namespace: '/'
+imu_topic: 'imu'
+accel_offset_x: 0.002
+accel_offset_y: 0.002
+accel_offset_z: 0.002
+accel_drift_x: 0.0
+accel_drift_y: 0.0
+accel_drift_z: 0.0
+accel_noise_x: 0.00008
+accel_noise_y: 0.00008
+accel_noise_z: 0.00008
+rate_offset_x: 0.25
+rate_offset_y: 0.25
+rate_offset_z: 0.25
+rate_drift_x: 0.0
+rate_drift_y: 0.0
+rate_drift_z: 0.0
+rate_noise_x: 0.03
+rate_noise_y: 0.03
+rate_noise_z: 0.03
+heading_offset: 0.003
+heading_drift: 0.0
+heading_noise: 0.0001
+
diff --git a/urdf/imu.gazebo b/urdf/imu.gazebo
index 8af3104..04418d1 100644
--- a/urdf/imu.gazebo
+++ b/urdf/imu.gazebo
@@ -3,21 +3,25 @@
   <xacro:macro name="microstrain_imu_gazebo" params="name config">
     <xacro:property name="properties" value="${load_yaml(config)}"/>
 
+    <gazebo reference="${name}_microstrain_imu">
+      <material>Gazebo/Black</material>
+    </gazebo>
+
     <gazebo>
       <plugin name="${name}_microstrain_imu_sim" filename="libhector_gazebo_ros_imu.so">
         <updateRate>${properties['rate']}</updateRate>
         <robotNamespace>${properties['namespace']}</robotNamespace>
         <bodyName>${name}_microstrain_imu</bodyName>
         <topicName>${properties['imu_topic']}</topicName>
-        <accelOffset>0.002 0.002 0.002</accelOffset>
-        <accelDrift>0.0 0.0 0.0</accelDrift>
-        <accelGaussianNoise>0.00008 0.00008 0.00008</accelGaussianNoise>
-        <rateOffset>0.25 0.25 0.25</rateOffset>
-        <rateDrift>0.0 0.0 0.0</rateDrift>
-        <rateGaussianNoise>0.03 0.03 0.03</rateGaussianNoise>
-        <headingOffset>0.003</headingOffset>
-        <headingDrift>0.0</headingDrift>
-        <headingGaussianNoise>0.0001</headingGaussianNoise>
+        <accelOffset>${properties['accel_offset_x']} ${properties['accel_offset_y']} ${properties['accel_offset_z']}</accelOffset>
+        <accelDrift>${properties['accel_drift_x']} ${properties['accel_drift_y']} ${properties['accel_drift_z']}</accelDrift>
+        <accelGaussianNoise>${properties['accel_noise_x']} ${properties['accel_noise_y']} ${properties['accel_noise_z']}</accelGaussianNoise>
+        <rateOffset>${properties['rate_offset_x']} ${properties['rate_offset_y']} ${properties['rate_offset_z']}</rateOffset>
+        <rateDrift>${properties['rate_drift_x']} ${properties['rate_drift_y']} ${properties['rate_drift_z']}</rateDrift>
+        <rateGaussianNoise>${properties['rate_noise_x']} ${properties['rate_noise_y']} ${properties['rate_noise_z']}</rateGaussianNoise>
+        <headingOffset>${properties['heading_offset']}</headingOffset>
+        <headingDrift>${properties['heading_drift']}</headingDrift>
+        <headingGaussianNoise>${properties['heading_noise']}</headingGaussianNoise>
       </plugin>
     </gazebo>
   </xacro:macro>
-- 
GitLab