From 29728253c7a2235e07e5c90a29b836a6ba4c8e09 Mon Sep 17 00:00:00 2001
From: fherrero <fherrero@iri.upc.edu>
Date: Thu, 28 Feb 2019 19:31:57 +0100
Subject: [PATCH] Update launch and config files

---
 launch/domap.launch                           |  18 -
 launch/helena_amcl_lab.launch                 |  52 ---
 launch/helena_move_base.launch                |  39 --
 launch/helena_navigation_test.launch          |  32 --
 launch/include/amcl.launch                    |   6 +-
 .../{gmapping.launch => gmapping_old.launch}  |   0
 launch/include/map_server.launch              |   2 +-
 launch/include/pointcloud_to_laserscan.launch |  43 ++
 launch/nav.launch                             | 114 ++++--
 launch/nav_mapping.launch                     |  85 ++++
 launch/nav_sim_test.launch                    |  67 ----
 launch/teleop.launch                          |  13 -
 params/{amcl_default.yaml => amcl.yaml}       |   0
 .../global_planner/global_planner_params.yaml |  22 ++
 params/gmapping.yaml                          |  30 ++
 params/local_planner/dwa_params.yaml          |  53 +++
 params/{helena_mux.yaml => mux.yaml}          |  12 +-
 rviz/ana_nav.rviz                             | 366 ++++++++++--------
 18 files changed, 516 insertions(+), 438 deletions(-)
 delete mode 100644 launch/domap.launch
 delete mode 100755 launch/helena_amcl_lab.launch
 delete mode 100755 launch/helena_move_base.launch
 delete mode 100755 launch/helena_navigation_test.launch
 rename launch/include/{gmapping.launch => gmapping_old.launch} (100%)
 create mode 100644 launch/include/pointcloud_to_laserscan.launch
 create mode 100644 launch/nav_mapping.launch
 delete mode 100644 launch/nav_sim_test.launch
 delete mode 100644 launch/teleop.launch
 rename params/{amcl_default.yaml => amcl.yaml} (100%)
 create mode 100644 params/global_planner/global_planner_params.yaml
 create mode 100644 params/gmapping.yaml
 create mode 100644 params/local_planner/dwa_params.yaml
 rename params/{helena_mux.yaml => mux.yaml} (68%)

diff --git a/launch/domap.launch b/launch/domap.launch
deleted file mode 100644
index fab41f0..0000000
--- a/launch/domap.launch
+++ /dev/null
@@ -1,18 +0,0 @@
-<?xml version="1.0"?>
-<!-- -->
-<launch>
-  
-  <arg name="resolution" default="0.05"/>
-  
-  <include file="$(find helena_base)/machines/$(optenv ROBOT helena)_$(optenv ROS_MODE sim).machines" />
-
-  <include file="$(find helena_rosnav)/launch/include/gmapping.launch" >
-    <arg name="resolution" value="$(arg resolution)"/>
-  </include>
-
-
-  <include file="$(find helena_rosnav)/launch/include/cmd_vel_mux.launch" />
-<!--  <include file="$(find helena_rosnav)/launch/include/velocity_smoother.launch" />-->
-  <include file="$(find helena_rosnav)/launch/include/move_base.launch" />
-
-</launch>
diff --git a/launch/helena_amcl_lab.launch b/launch/helena_amcl_lab.launch
deleted file mode 100755
index 19067a5..0000000
--- a/launch/helena_amcl_lab.launch
+++ /dev/null
@@ -1,52 +0,0 @@
-<!-- -->
-<launch>
-
-  <!-- load robot defined machines -->
-  <include file="$(find helena_base)/machines/$(env ROBOT).machines" />
-
-  <group ns="$(env ROBOT)">
-  
-    <!-- Map Server -->
-      <!-- published topics: /$(env ROBOT)/map -->
-      <!-- subscribed topics: -->
-      <!-- service clients: -->
-      <!-- service servers: -->
-      <!-- action clients: -->
-      <!-- action servers: -->
-    <node name="map_server" 
-          pkg ="map_server" 
-          type="map_server" 
-          args="$(find tibi_dabo_rosnav)/maps/mr_lab.yaml" 
-          machine="embedded">
-          <param name="frame_id" value="/map" />
-    </node>
-
-    <!-- AMCL -->
-      <!-- published topics: -->
-      <!-- subscribed topics: /$(env ROBOT)/sensors/front_laser_scan -->
-      <!--                    /$(env ROBOT)/tf -->
-      <!--                    /$(env ROBOT)/initialpose -->
-      <!-- service clients: -->
-      <!-- service servers: -->
-      <!-- action clients: -->
-      <!-- action servers: -->
-    <node name="amcl" 
-          pkg ="amcl" 
-          type="amcl"
-          machine="embedded">
-      <remap from="scan" 
-               to="/$(env ROBOT)/sensors/front_laser_scan"/>
-      <param name="odom_frame_id"    value="/$(env ROBOT)/odom" />
-      <param name="base_frame_id"    value="/$(env ROBOT)/base_link" />
-      <param name="global_frame_id"  value="/map" />
-      <param name="min_particles"    value="100" />
-      <param name="max_particles"    value="500" />
-      <param name="initial_pose_x"   value="0" />
-      <param name="initial_pose_y"   value="0" />
-      <param name="initial_pose_a"   value="0" />
-      <param name="gui_publish_rate" value="1" />
-    </node>
-
-  </group>
-
-</launch>
diff --git a/launch/helena_move_base.launch b/launch/helena_move_base.launch
deleted file mode 100755
index f898b8e..0000000
--- a/launch/helena_move_base.launch
+++ /dev/null
@@ -1,39 +0,0 @@
-<!-- -->
-<launch>
-
-  <!-- load robot defined machines -->
-  <include file="$(find helena_base)/machines/$(env ROBOT).machines" />
-
-  <group ns="$(env ROBOT)"> 
-
-    <node pkg ="move_base" 
-          type="move_base" 
-          name="move_base"
-          machine="embedded" 
-          output="screen">
-
-      <param name="~/controller_frequency"      value="20"   type="double"/> <!-- default= 20 -->
-      <param name="~/planner_frequency"         value="0"    type="double"/> <!-- default= 0 -->
-      <param name="~/recovery_behavior_enabled" value="true" type="bool"/>   <!-- default= true -->
-      <param name="~/clearing_rotation_allowed" value="true" type="bool"/>   <!-- default= true -->
-
-      <remap from="/$(env ROBOT)/cmd_vel" to="/$(env ROBOT)/helena/cmd_vel" />
-      <remap from="/$(env ROBOT)/odom" to="/$(env ROBOT)/helena/pose" />
-
-      <!-- Base local planner -->
-      <rosparam file="$(find helena_rosnav)/config/base_local_planner_params.yaml" command="load" />
-
-      <!-- Local costmap configs: common + local -->
-      <rosparam file="$(find helena_rosnav)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
-      <rosparam file="$(find helena_rosnav)/config/local_costmap_params.yaml" command="load" />
-
-      <!-- Global costmap config: common + global -->
-      <rosparam file="$(find helena_rosnav)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
-      <rosparam file="$(find helena_rosnav)/config/global_costmap_params.yaml" command="load" /> 
-
-    </node>
-
-
-  </group>
-
-</launch>
diff --git a/launch/helena_navigation_test.launch b/launch/helena_navigation_test.launch
deleted file mode 100755
index ef4731d..0000000
--- a/launch/helena_navigation_test.launch
+++ /dev/null
@@ -1,32 +0,0 @@
-<!-- -->
-<launch>
-
-  <!-- load robot defined machines -->
-  <include file="$(find helena_base)/machines/$(env ROBOT).machines" />
-
-  <include file="$(find helena_base)/launch/helena_base.launch">
-  </include>
-
-  <!-- AMCL + Map Server-->
-    <!-- published topics: /$(env ROBOT)/map -->
-    <!-- subscribed topics: /$(env ROBOT)/sensors/front_laser_scan -->
-    <!--                    /$(env ROBOT)/tf -->
-    <!--                    /$(env ROBOT)/initialpose -->
-    <!-- service clients: -->
-    <!-- service servers: -->
-    <!-- action clients: -->
-    <!-- action servers: -->
-  <include file="$(find helena_rosnav)/launch/helena_amcl_lab.launch">
-  </include>
-
-  <!-- ROS Navigation: move_base -->
-  <include file="$(find helena_rosnav)/launch/helena_move_base.launch">
-  </include>  
-
-  <node name="rviz" 
-        pkg ="rviz" 
-        type="rviz"
-        machine="monitor"
-        args="-d $(find helena_rosnav)/config/$(env ROBOT)_rosnav.vcg" />
-
-</launch>
diff --git a/launch/include/amcl.launch b/launch/include/amcl.launch
index aab3409..8ca8dfc 100644
--- a/launch/include/amcl.launch
+++ b/launch/include/amcl.launch
@@ -36,9 +36,9 @@
     <param name="odom_frame_id"    value="/ana/odom" />
     <param name="base_frame_id"    value="/ana/base_link" />
     <param name="global_frame_id"  value="$(arg map_frame_id)" />
-    <param name="initial_pose_x"   value="$(arg x)" />
-    <param name="initial_pose_y"   value="$(arg y)" />
-    <param name="initial_pose_a"   value="$(arg a)" />
+    <param name="initial_pose_x"   value="$(arg initial_x)" />
+    <param name="initial_pose_y"   value="$(arg initial_y)" />
+    <param name="initial_pose_a"   value="$(arg initial_a)" />
     <rosparam file="$(arg config)" command="load"/>
   </node>
 
diff --git a/launch/include/gmapping.launch b/launch/include/gmapping_old.launch
similarity index 100%
rename from launch/include/gmapping.launch
rename to launch/include/gmapping_old.launch
diff --git a/launch/include/map_server.launch b/launch/include/map_server.launch
index 2bf4fe1..9de03d3 100644
--- a/launch/include/map_server.launch
+++ b/launch/include/map_server.launch
@@ -2,7 +2,7 @@
 <!-- -->
 <launch>
 
-  <arg name="map"          default="test"/>
+  <arg name="map"          default="empty"/>
   <arg name="map_frame_id" default="map"/>
 
   <node name="map_server" 
diff --git a/launch/include/pointcloud_to_laserscan.launch b/launch/include/pointcloud_to_laserscan.launch
new file mode 100644
index 0000000..bbc0542
--- /dev/null
+++ b/launch/include/pointcloud_to_laserscan.launch
@@ -0,0 +1,43 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="ns"            default="robot"/>
+  <arg name="scan_topic"    default="$(arg ns)/scan"/>
+  <arg name="cloud_topic"   default="$(arg ns/points"/>
+  <arg name="output" default="screen" />
+  <arg name="launch_prefix" default="" />
+  
+  <group ns="$(arg ns)">
+
+    <node name="pointcloud_to_laserscan"
+          pkg ="pointcloud_to_laserscan"
+          type="pointcloud_to_laserscan_node"
+          output="$(arg output)"
+          launch-prefix="$(arg launch_prefix)">
+      <remap from="/$(arg ns)/scan"     to="$(arg scan_topic)"/>
+      <remap from="/$(arg ns)/cloud_in" to="$(arg cloud_topic)"/>
+      <rosparam>
+          target_frame: "" #camera_link # Leave disabled to output scan in pointcloud frame
+          transform_tolerance: 0.01
+          min_height: -0.125
+          max_height: 0.125
+          angle_min: -3.14159 #-1.5708 # -M_PI/2
+          angle_max: 3.14159  #1.5708 # M_PI/2
+          angle_increment: 0.0087 # M_PI/360.0
+          scan_time: 0.3333
+          range_min: 0.1
+          range_max: 40.0
+          use_inf: true
+
+          # Concurrency level, affects number of pointclouds queued for processing and number of threads used
+          # 0 : Detect number of cores
+          # 1 : Single threaded
+          # 2->inf : Parallelism level
+          concurrency_level: 1
+      </rosparam>
+    </node>
+    
+  </group>
+
+</launch>
\ No newline at end of file
diff --git a/launch/nav.launch b/launch/nav.launch
index 8f4ac02..b0ede30 100644
--- a/launch/nav.launch
+++ b/launch/nav.launch
@@ -1,53 +1,85 @@
 <?xml version="1.0"?>
 <!-- -->
 <launch>
- 
-  <arg name="use_map_server" default="true"/> 
-  <arg name="map_frame_id"   default="map"/>
-  <arg name="map"            default=""/>
 
-  <arg name="use_amcl"     default="true"/>
-  <arg name="amcl_config"  default="$(find iri_ana_rosnav)/params/amcl_default.yaml"/>
-  <arg name="use_fake_loc" default="false"/>
-  <arg name="initial_x"    default="0.0"/>
-  <arg name="initial_y"    default="0.0"/>
-  <arg name="initial_yaw"  default="0.0"/>
-  
-  <arg name="use_cmd_vel_mux"  default="false"/>
-  <arg name="cmd_vel_mux_config"  default="$(find iri_ana_rosnav)/params/cmd_vel_mux_default.yaml"/>
+  <arg name="rviz"           default="true"/>
 
+  <arg name="ns"             default="ana"/>
+  <arg name="path"           default="$(find iri_ana_rosnav)"/>
+  <arg name="map_frame_id"   default="map"/>
+  <arg name="odom_frame_id"  default="$(arg ns)/odom"/>
+  <arg name="base_frame_id"  default="$(arg ns)/base_footprint"/>
+  <arg name="map_topic"      default="/$(arg ns)/map"/>
+  <arg name="map_service"    default="/$(arg ns)/static_map"/>
+  <arg name="odom_topic"     default="/$(arg ns)/odom"/>
+  <arg name="cmd_vel_topic"  default="/$(arg ns)/navigation/cmd_vel"/>
+  <arg name="scan_topic"     default="/$(arg ns)/scan"/>
+  <arg name="use_map"        default="true"/>
+  <arg name="use_map_server" default="true"/>
+    <arg name="map_name"       default="willow"/>
+  <arg name="use_amcl"       default="true"/>
+    <arg name="amcl_config"    default="$(arg path)/params/amcl.yaml"/>
+    <arg name="initial_x"      default="0.0"/>
+    <arg name="initial_y"      default="0.0"/>
+    <arg name="initial_yaw"    default="0.0"/>
+  <arg name="use_fake_loc"   default="false"/>
+  <arg name="use_gmapping"   default="false"/>
+    <arg name="gmapping_scan_topic"     default="/$(arg ns)/front_hokuyo_scan"/>
+    <arg name="gmapping_config" default="$(arg path)/params/gmapping.yaml"/>
+    <arg name="resolution"     default="0.1"/>
+  <arg name="use_cmd_vel_mux"      default="true"/>
+  <arg name="nodelet_manager_name" default="nodelet_manager"/>
+  <arg name="cmd_vel_mux_config"   default="$(arg path)/params/mux.yaml"/>
   <arg name="local_planner"  default="dwa"/>
-  <arg name="global_planner" default="global"/>
-
-  <group if="$(arg use_map_server)">
-    <include file="$(find iri_ana_rosnav)/launch/include/map_server.launch">
-      <arg name="frame_id" value="$(arg map_frame_id)"/>
-      <arg name="map" value="$(arg map)"/>
-    </include>
-  </group>
-
-  <group if="$(arg use_map_server)">
-    <group if="$(arg use_amcl)">
-      <include file="$(find iri_ana_rosnav)/launch/include/amcl.launch">
-        <arg name="config"       value="$(arg amcl_config)"/>
-        <arg name="map_frame_id" value="$(arg map_frame_id)"/>
-        <arg name="initial_x"    value="$(arg initial_x)"/>
-        <arg name="initial_y"    value="$(arg initial_y)"/>
-        <arg name="initial_a"    value="$(arg initial_yaw)"/>
-      </include>
-    </group>
-  </group>
+  <arg name="global_planner" default="global_planner"/>
+  <arg name="output"         default="screen" />
+  <arg name="launch_prefix"  default="" />
 
-  <group if="$(arg use_cmd_vel_mux)"> 
-    <include file="$(find iri_ana_rosnav)/launch/include/cmd_vel_mux.launch">
-      <arg name="config" value="$(arg cmd_vel_mux_config)"/>
-    </include>
-  </group>
-
-  <include file="$(find iri_ana_rosnav)/launch/include/move_base.launch">
-    <arg name="use_map"        value="$(arg use_map_server)"/> 
+  <include file="$(find iri_rosnav)/launch/nav.launch">
+    <arg name="ns"             value="$(arg ns)"/>
+    <arg name="path"           value="$(arg path)"/>
+    <arg name="map_frame_id"   value="$(arg map_frame_id)"/>
+    <arg name="odom_frame_id"  value="$(arg odom_frame_id)"/>
+    <arg name="base_frame_id"  value="$(arg base_frame_id)"/>
+    <arg name="map_topic"      value="$(arg map_topic)"/>
+    <arg name="map_service"    value="$(arg map_service)"/>
+    <arg name="odom_topic"     value="$(arg odom_topic)"/>
+    <arg name="cmd_vel_topic"  value="$(arg cmd_vel_topic)"/>
+    <arg name="scan_topic"     value="$(arg scan_topic)"/>
+    <arg name="use_map_server" value="$(arg use_map_server)"/> 
+    <arg name="map_name"       value="$(arg map_name)"/>
+    <arg name="use_amcl"       value="$(arg use_amcl)"/>
+    <arg name="amcl_config"    value="$(arg amcl_config)"/>
+    <arg name="initial_x"      value="$(arg initial_x)"/>
+    <arg name="initial_y"      value="$(arg initial_y)"/>
+    <arg name="initial_yaw"    value="$(arg initial_yaw)"/>
+    <arg name="use_fake_loc"   value="$(arg use_fake_loc)"/>
+    <arg name="use_gmapping"        value="$(arg use_gmapping)"/>
+    <arg name="gmapping_scan_topic" value="/$(arg gmapping_scan_topic)"/>
+    <arg name="gmapping_config"     value="$(arg gmapping_config)"/>
+    <arg name="resolution"          value="$(arg resolution)"/>
+    <arg name="use_cmd_vel_mux"      value="$(arg use_cmd_vel_mux)"/>
+    <arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)"/>
+    <arg name="cmd_vel_mux_config"   value="$(arg cmd_vel_mux_config)"/>
     <arg name="local_planner"  value="$(arg local_planner)"/>
     <arg name="global_planner" value="$(arg global_planner)"/>
+    <arg name="output"         value="$(arg output)" />
+    <arg name="launch_prefix"  value="$(arg launch_prefix)" />
+  </include>
+  
+  <include file="$(arg path)/launch/include/pointcloud_to_laserscan.launch">
+    <arg name="ns"             value="$(arg ns)"/>
+    <arg name="scan_topic"     value="$(arg scan_topic)"/>
+    <arg name="cloud_topic"    value="/$(arg ns)/sensors/velodyne_points"/>
+    <arg name="output"         value="$(arg output)" />
+    <arg name="launch_prefix"  value="$(arg launch_prefix)" />
   </include>
+  
+  <node name="rviz"
+        pkg="rviz"
+        type="rviz"
+        if="$(arg rviz)"
+        args="-d $(arg path)/rviz/$(arg ns).rviz">
+  </node>
 
 </launch>
diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch
new file mode 100644
index 0000000..4c90506
--- /dev/null
+++ b/launch/nav_mapping.launch
@@ -0,0 +1,85 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="rviz"           default="true"/>
+
+  <arg name="ns"             default="ana"/>
+  <arg name="path"           default="$(find iri_ana_rosnav)"/>
+  <arg name="map_frame_id"   default="map"/>
+  <arg name="odom_frame_id"  default="$(arg ns)/odom"/>
+  <arg name="base_frame_id"  default="$(arg ns)/base_footprint"/>
+  <arg name="map_topic"      default="/$(arg ns)/map"/>
+  <arg name="map_service"    default="/$(arg ns)/static_map"/>
+  <arg name="odom_topic"     default="/$(arg ns)/odom"/>
+  <arg name="cmd_vel_topic"  default="/$(arg ns)/navigation/cmd_vel"/>
+  <arg name="scan_topic"     default="/$(arg ns)/scan"/>
+  <arg name="use_map"        default="true"/>
+  <arg name="use_map_server" default="false"/>
+    <arg name="map_name"       default="willow"/>
+  <arg name="use_amcl"       default="false"/>
+    <arg name="amcl_config"    default="$(arg path)/params/amcl.yaml"/>
+    <arg name="initial_x"      default="0.0"/>
+    <arg name="initial_y"      default="0.0"/>
+    <arg name="initial_yaw"    default="0.0"/>
+  <arg name="use_fake_loc"   default="false"/>
+  <arg name="use_gmapping"   default="true"/>
+    <arg name="gmapping_scan_topic"     default="/$(arg ns)/scan"/>
+    <arg name="gmapping_config" default="$(arg path)/params/gmapping.yaml"/>
+    <arg name="resolution"     default="0.1"/>
+  <arg name="use_cmd_vel_mux"      default="true"/>
+  <arg name="nodelet_manager_name" default="nodelet_manager"/>
+  <arg name="cmd_vel_mux_config"   default="$(arg path)/params/mux.yaml"/>
+  <arg name="local_planner"  default="dwa"/>
+  <arg name="global_planner" default="global_planner"/>
+  <arg name="output"         default="screen" />
+  <arg name="launch_prefix"  default="" />
+
+  <include file="$(find iri_rosnav)/launch/nav.launch">
+    <arg name="ns"             value="$(arg ns)"/>
+    <arg name="path"           value="$(arg path)"/>
+    <arg name="map_frame_id"   value="$(arg map_frame_id)"/>
+    <arg name="odom_frame_id"  value="$(arg odom_frame_id)"/>
+    <arg name="base_frame_id"  value="$(arg base_frame_id)"/>
+    <arg name="map_topic"      value="$(arg map_topic)"/>
+    <arg name="map_service"    value="$(arg map_service)"/>
+    <arg name="odom_topic"     value="$(arg odom_topic)"/>
+    <arg name="cmd_vel_topic"  value="$(arg cmd_vel_topic)"/>
+    <arg name="scan_topic"     value="$(arg scan_topic)"/>
+    <arg name="use_map_server" value="$(arg use_map_server)"/> 
+    <arg name="map_name"       value="$(arg map_name)"/>
+    <arg name="use_amcl"       value="$(arg use_amcl)"/>
+    <arg name="amcl_config"    value="$(arg amcl_config)"/>
+    <arg name="initial_x"      value="$(arg initial_x)"/>
+    <arg name="initial_y"      value="$(arg initial_y)"/>
+    <arg name="initial_yaw"    value="$(arg initial_yaw)"/>
+    <arg name="use_fake_loc"   value="$(arg use_fake_loc)"/>
+    <arg name="use_gmapping"        value="$(arg use_gmapping)"/>
+    <arg name="gmapping_scan_topic" value="/$(arg gmapping_scan_topic)"/>
+    <arg name="gmapping_config"     value="$(arg gmapping_config)"/>
+    <arg name="resolution"          value="$(arg resolution)"/>
+    <arg name="use_cmd_vel_mux"      value="$(arg use_cmd_vel_mux)"/>
+    <arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)"/>
+    <arg name="cmd_vel_mux_config"   value="$(arg cmd_vel_mux_config)"/>
+    <arg name="local_planner"  value="$(arg local_planner)"/>
+    <arg name="global_planner" value="$(arg global_planner)"/>
+    <arg name="output"         value="$(arg output)" />
+    <arg name="launch_prefix"  value="$(arg launch_prefix)" />
+  </include>
+  
+  <include file="$(arg path)/launch/include/pointcloud_to_laserscan.launch">
+    <arg name="ns"             value="$(arg ns)"/>
+    <arg name="scan_topic"     value="$(arg scan_topic)"/>
+    <arg name="cloud_topic"    value="/$(arg ns)/sensors/velodyne_points"/>
+    <arg name="output"         value="$(arg output)" />
+    <arg name="launch_prefix"  value="$(arg launch_prefix)" />
+  </include>
+  
+  <node name="rviz"
+        pkg="rviz"
+        type="rviz"
+        if="$(arg rviz)"
+        args="-d $(find iri_dabo_rosnav)/rviz/$(arg ns).rviz">
+  </node>
+
+</launch>
diff --git a/launch/nav_sim_test.launch b/launch/nav_sim_test.launch
deleted file mode 100644
index 5b058ef..0000000
--- a/launch/nav_sim_test.launch
+++ /dev/null
@@ -1,67 +0,0 @@
-<?xml version="1.0" encoding="UTF-8"?>
-<launch>
-
-  <arg name="use_map_server" default="false"/>
-  <arg name="map_frame_id"   default="map"/>
-  <arg name="map"            default=""/>
-
-  <arg name="use_amcl"     default="false"/>
-  <arg name="amcl_config"  default="$(find iri_ana_rosnav)/params/amcl_default.yaml"/>
-  <arg name="use_fake_loc" default="false"/>
-  <arg name="initial_x"    default="0.0"/>
-  <arg name="initial_y"    default="0.0"/>
-  <arg name="initial_yaw"  default="0.0"/>
-
-  <arg name="use_cmd_vel_mux"  default="false"/>
-  <arg name="cmd_vel_mux_config"  default="$(find iri_ana_rosnav)/params/cmd_vel_mux_default.yaml"/>
-
-  <arg name="local_planner"  default="dwa"/>
-  <arg name="global_planner" default="global"/>
-
-  <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
-  <include file="$(find gazebo_ros)/launch/empty_world.launch">
-    <arg name="paused"              value="false"/>
-    <arg name="use_sim_time"        value="true"/>
-    <arg name="extra_gazebo_args"   value=""/>
-    <arg name="gui"                 value="true"/>
-    <arg name="recording"           value="false"/>
-    <arg name="headless"            value="false"/>
-    <arg name="debug"               value="false"/>
-    <arg name="physics"             value="ode"/>
-    <arg name="verbose"             value="false"/>
-    <arg name="world_name"          value="worlds/empty.world"/>
-    <arg name="respawn_gazebo"      value="false"/>
-    <arg name="use_clock_frequency" value="false"/>
-    <arg name="pub_clock_frequency" value="100"/>
-  </include>
-
-  <include file="$(find iri_ana_gazebo)/launch/spawn_ana.launch">
-    <arg name="name"  value="ana"/>
-    <arg name="model" value="ana"/>
-    <arg name="x"   value="0.0"/>
-    <arg name="y"   value="0.0"/>
-    <arg name="yaw" value="0.0"/>
-  </include>
-
-  <include file="$(find iri_ana_rosnav)/launch/nav.launch">
-    <arg name="use_map_server"      value="$(arg use_map_server)"/>
-    <arg name="map_frame_id"        value="$(arg map_frame_id)"/>
-    <arg name="map"                 value="$(arg map)"/>
-    <arg name="use_amcl"            value="$(arg use_amcl)"/>
-    <arg name="amcl_config"         value="$(arg amcl_config)"/>
-    <arg name="use_fake_loc"        value="$(arg use_fake_loc)"/>
-    <arg name="initial_x"           value="$(arg initial_x)"/>
-    <arg name="initial_y"           value="$(arg initial_y)"/>
-    <arg name="initial_yaw"         value="$(arg initial_yaw)"/>
-    <arg name="use_cmd_vel_mux"     value="$(arg use_cmd_vel_mux)"/>
-    <arg name="cmd_vel_mux_config"  value="$(arg cmd_vel_mux_config)"/>
-    <arg name="local_planner"       value="$(arg local_planner)"/>
-    <arg name="global_planner"      value="$(arg global_planner)"/>
-  </include>
-
-  <node name="rviz"
-        pkg="rviz"
-        type="rviz"
-        args="-d $(find iri_ana_rosnav)/rviz/ana_nav.rviz"/>
-</launch>
-
diff --git a/launch/teleop.launch b/launch/teleop.launch
deleted file mode 100644
index a54676c..0000000
--- a/launch/teleop.launch
+++ /dev/null
@@ -1,13 +0,0 @@
-<?xml version="1.0"?>
-<!-- -->
-<launch>
-  
-  <arg name="map" default="test"/>
-  
-  <include file="$(find helena_base)/machines/$(optenv ROBOT helena)_$(optenv ROS_MODE sim).machines" />
-  
-  <include file="$(find helena_rosnav)/launch/include/cmd_vel_mux.launch" />
-  <include file="$(find helena_rosnav)/launch/include/velocity_smoother.launch" />
-
-  <include file="$(find helena_base)/launch/joystick_teleop.launch" />
-</launch>
diff --git a/params/amcl_default.yaml b/params/amcl.yaml
similarity index 100%
rename from params/amcl_default.yaml
rename to params/amcl.yaml
diff --git a/params/global_planner/global_planner_params.yaml b/params/global_planner/global_planner_params.yaml
new file mode 100644
index 0000000..43e309e
--- /dev/null
+++ b/params/global_planner/global_planner_params.yaml
@@ -0,0 +1,22 @@
+base_global_planner: "global_planner/GlobalPlanner"
+
+GlobalPlanner: #default
+  allow_unknown: false 
+  default_tolerance: 0.0 
+  publish_potential: false 
+  publish_scale: 100
+  old_navfn_behavior: false 
+  planner_costmap_publish_frequency: 0.0
+#planner to use
+  use_dijkstra: true 
+  use_quadratic: true 
+  use_grid_path: false 
+# planner parameters
+  lethal_cost: 253
+  neutral_cost: 50
+  cost_factor: 3.0
+  planner_window_x: 0.0
+  planner_window_y: 0.0
+# orientation fileter
+  orientation_mode: 0
+  orientation_window_size: 1 
diff --git a/params/gmapping.yaml b/params/gmapping.yaml
new file mode 100644
index 0000000..d7c5f34
--- /dev/null
+++ b/params/gmapping.yaml
@@ -0,0 +1,30 @@
+map_update_interval: 5.0
+maxUrange: 29.0
+sigma:      0.05
+kernelSize: 1
+lstep:      0.05
+astep:      0.05
+iterations: 5
+lsigma:     0.075
+ogain:      3.0
+lskip: 0
+srr: 0.1
+srt: 0.2
+str: 0.1
+stt: 0.2
+linearUpdate:      0.5
+angularUpdate:     0.5
+temporalUpdate:    10.0
+resampleThreshold: 0.5
+particles:         80
+
+xmin: -5.0
+ymin: -5.0
+xmax:  5.0
+ymax:  5.0
+
+delta: 0.1
+llsamplerange: 0.01
+llsamplestep:  0.01
+lasamplerange: 0.005
+lasamplestep:  0.005
\ No newline at end of file
diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml
new file mode 100644
index 0000000..8bef897
--- /dev/null
+++ b/params/local_planner/dwa_params.yaml
@@ -0,0 +1,53 @@
+base_local_planner: "dwa_local_planner/DWAPlannerROS"
+latch_xy_goal_tolerance: true 
+
+DWAPlannerROS:
+# robot configuration parameters
+  max_trans_vel: 0.5
+  min_trans_vel: 0.1
+  max_vel_x: 0.5
+  min_vel_x: -0.5
+  max_vel_y: 0.0 
+  min_vel_y: 0.0 
+  max_rot_vel: 2.0
+  min_rot_vel: 0.2 
+  acc_lim_theta: 3.0
+  acc_lim_x: 1.0
+  acc_lim_y: 0.0 
+  acc_limit_trans: 1.0
+  rot_stopped_vel: 0.1
+  trans_stopped_vel: 0.1
+
+# goal tolerance parameters
+  xy_goal_tolerance: 0.1 
+  yaw_goal_tolerance: 0.1 
+
+# Forward simulation parameters
+  sim_time: 2.5
+  sim_granularity: 0.1
+  angular_sim_granularity: 0.1
+  vx_samples: 21
+  vy_samples: 1 
+  vth_samples: 20
+  controller_frequency: 20.0 # defines the sim_period
+
+# Trajectory scoring parameters
+  path_distance_bias: 32.0
+  goal_distance_bias: 32.0
+  occdist_scale: 0.01
+  twirling_scale: 0.0
+  stop_time_buffer: 0.2
+  forward_point_distance: 0.325
+  scaling_speed: 0.25
+  max_scaling_factor: 0.2
+
+# Oscillation prevention parameters
+  oscillation_reset_dist: 0.05
+  oscillation_reset_angle: 0.2
+  
+# global plan parameters
+  prune_plan: true
+
+  #not in dynamic reconfigure
+  publish_traj_pc: false
+  publish_cost_grid_pc: false
diff --git a/params/helena_mux.yaml b/params/mux.yaml
similarity index 68%
rename from params/helena_mux.yaml
rename to params/mux.yaml
index 58aff0e..8546c6e 100644
--- a/params/helena_mux.yaml
+++ b/params/mux.yaml
@@ -1,27 +1,27 @@
 subscribers:
   - name:        "Default input"
-    topic:       "/helena/default/cmd_vel"
+    topic:       "/ana/default/cmd_vel"
     timeout:     0.1
     priority:    0
     short_desc:  "The default cmd_vel, controllers unaware that we are multiplexing cmd_vel should come here"
 
   - name:        "Platform orientation"
-    topic:       "/helena/orientation/cmd_vel"
+    topic:       "/ana/orientation/cmd_vel"
     timeout:     0.1
     priority:    4
     short_desc:  "Platform orientation to people"
 
   - name:        "Navigation stack"
-    topic:       "/helena/navigation/cmd_vel"
+    topic:       "/ana/navigation/cmd_vel"
     timeout:     0.5
     priority:    5
     short_desc:  "Navigation stack controller"
 
   - name:        "Teleop"
-    topic:       "/helena/teleop/cmd_vel"
+    topic:       "/ana/teleop/cmd_vel"
     timeout:     0.1
     priority:    10
     short_desc:  "Teleop wii/ps3 pad"
 
-#publisher:       "/helena/mux/cmd_vel"
-publisher:       "/helena/cmd_vel"
+#publisher:       "/ana/mux/cmd_vel"
+publisher:       "/ana/cmd_vel"
diff --git a/rviz/ana_nav.rviz b/rviz/ana_nav.rviz
index 8497916..8adda43 100644
--- a/rviz/ana_nav.rviz
+++ b/rviz/ana_nav.rviz
@@ -4,10 +4,11 @@ Panels:
     Name: Displays
     Property Tree Widget:
       Expanded:
-        - /Global Options1
-        - /Status1
+        - /Sensors1
+        - /Nav1
+        - /Nav1/Map1/Status1
       Splitter Ratio: 0.5
-    Tree Height: 522
+    Tree Height: 545
   - Class: rviz/Selection
     Name: Selection
   - Class: rviz/Tool Properties
@@ -26,7 +27,7 @@ Panels:
     Experimental: false
     Name: Time
     SyncMode: 0
-    SyncSource: Velodyne
+    SyncSource: realsense_color
 Visualization Manager:
   Class: ""
   Displays:
@@ -338,161 +339,194 @@ Visualization Manager:
                 {}
       Update Interval: 0
       Value: true
-    - Alpha: 1
-      Autocompute Intensity Bounds: true
-      Autocompute Value Bounds:
-        Max Value: 0.00564962626
-        Min Value: -0.00647342205
-        Value: true
-      Axis: Z
-      Channel Name: intensity
-      Class: rviz/PointCloud2
-      Color: 255; 255; 255
-      Color Transformer: Intensity
-      Decay Time: 0
-      Enabled: true
-      Invert Rainbow: false
-      Max Color: 255; 255; 255
-      Max Intensity: 0
-      Min Color: 0; 0; 0
-      Min Intensity: 0
-      Name: Velodyne
-      Position Transformer: XYZ
-      Queue Size: 10
-      Selectable: true
-      Size (Pixels): 3
-      Size (m): 0.00999999978
-      Style: Points
-      Topic: /ana/sensors/velodyne_points
-      Unreliable: false
-      Use Fixed Frame: true
-      Use rainbow: true
-      Value: true
-    - Alpha: 1
-      Class: rviz_plugin_tutorials/Imu
-      Color: 204; 51; 204
-      Enabled: false
-      History Length: 1
-      Name: Imu
-      Topic: /ana/sensors/imu
-      Unreliable: false
-      Value: false
-    - Class: rviz/Image
-      Enabled: true
-      Image Topic: /ana/sensors/nav_cam/color/image_raw
-      Max Value: 1
-      Median window: 5
-      Min Value: 0
-      Name: realsense_color
-      Normalize Range: true
-      Queue Size: 2
-      Transport Hint: raw
-      Unreliable: false
-      Value: true
-    - Alpha: 1
-      Autocompute Intensity Bounds: true
-      Autocompute Value Bounds:
-        Max Value: 10
-        Min Value: -10
-        Value: true
-      Axis: Z
-      Channel Name: intensity
-      Class: rviz/PointCloud2
-      Color: 255; 255; 255
-      Color Transformer: RGB8
-      Decay Time: 0
-      Enabled: true
-      Invert Rainbow: false
-      Max Color: 255; 255; 255
-      Max Intensity: 4096
-      Min Color: 0; 0; 0
-      Min Intensity: 0
-      Name: realsense_pointcloud
-      Position Transformer: XYZ
-      Queue Size: 10
-      Selectable: true
-      Size (Pixels): 3
-      Size (m): 0.00999999978
-      Style: Points
-      Topic: /ana/sensors/nav_cam/depth_registered/points
-      Unreliable: false
-      Use Fixed Frame: true
-      Use rainbow: true
-      Value: true
-    - Alpha: 1
-      Buffer Length: 1
-      Class: rviz/Path
-      Color: 25; 255; 0
-      Enabled: true
-      Head Diameter: 0.300000012
-      Head Length: 0.200000003
-      Length: 0.300000012
-      Line Style: Lines
-      Line Width: 0.0299999993
-      Name: global_plan
-      Offset:
-        X: 0
-        Y: 0
-        Z: 0
-      Pose Color: 255; 85; 255
-      Pose Style: None
-      Radius: 0.0299999993
-      Shaft Diameter: 0.100000001
-      Shaft Length: 0.100000001
-      Topic: /move_base/GlobalPlanner/plan
-      Unreliable: false
-      Value: true
-    - Alpha: 1
-      Buffer Length: 1
-      Class: rviz/Path
-      Color: 25; 255; 0
-      Enabled: true
-      Head Diameter: 0.300000012
-      Head Length: 0.200000003
-      Length: 0.300000012
-      Line Style: Lines
-      Line Width: 0.0299999993
-      Name: local_plan
-      Offset:
-        X: 0
-        Y: 0
-        Z: 0
-      Pose Color: 255; 85; 255
-      Pose Style: None
-      Radius: 0.0299999993
-      Shaft Diameter: 0.100000001
-      Shaft Length: 0.100000001
-      Topic: /move_base/DWAPlannerROS/local_plan
-      Unreliable: false
-      Value: true
-    - Alpha: 0.699999988
-      Class: rviz/Map
-      Color Scheme: map
-      Draw Behind: false
-      Enabled: true
-      Name: global_costmap
-      Topic: /move_base/global_costmap/costmap
-      Unreliable: false
-      Use Timestamp: false
-      Value: true
-    - Alpha: 0.699999988
-      Class: rviz/Map
-      Color Scheme: map
-      Draw Behind: false
+    - Class: rviz/Group
+      Displays:
+        - Alpha: 1
+          Class: rviz_plugin_tutorials/Imu
+          Color: 204; 51; 204
+          Enabled: false
+          History Length: 1
+          Name: Imu
+          Topic: /ana/sensors/imu
+          Unreliable: false
+          Value: false
+        - Class: rviz/Image
+          Enabled: true
+          Image Topic: /ana/sensors/nav_cam/color/image_raw
+          Max Value: 1
+          Median window: 5
+          Min Value: 0
+          Name: realsense_color
+          Normalize Range: true
+          Queue Size: 2
+          Transport Hint: raw
+          Unreliable: false
+          Value: true
+        - Alpha: 1
+          Autocompute Intensity Bounds: true
+          Autocompute Value Bounds:
+            Max Value: 10
+            Min Value: -10
+            Value: true
+          Axis: Z
+          Channel Name: intensity
+          Class: rviz/PointCloud2
+          Color: 255; 255; 255
+          Color Transformer: RGB8
+          Decay Time: 0
+          Enabled: true
+          Invert Rainbow: false
+          Max Color: 255; 255; 255
+          Max Intensity: 4096
+          Min Color: 0; 0; 0
+          Min Intensity: 0
+          Name: realsense_pointcloud
+          Position Transformer: XYZ
+          Queue Size: 10
+          Selectable: true
+          Size (Pixels): 3
+          Size (m): 0.00999999978
+          Style: Points
+          Topic: /ana/sensors/nav_cam/depth_registered/points
+          Unreliable: false
+          Use Fixed Frame: true
+          Use rainbow: true
+          Value: true
+        - Alpha: 1
+          Autocompute Intensity Bounds: true
+          Autocompute Value Bounds:
+            Max Value: 0.00564962626
+            Min Value: -0.00647342205
+            Value: true
+          Axis: Z
+          Channel Name: intensity
+          Class: rviz/PointCloud2
+          Color: 255; 255; 255
+          Color Transformer: Intensity
+          Decay Time: 0
+          Enabled: true
+          Invert Rainbow: false
+          Max Color: 255; 255; 255
+          Max Intensity: 999999
+          Min Color: 0; 0; 0
+          Min Intensity: -999999
+          Name: Velodyne
+          Position Transformer: XYZ
+          Queue Size: 10
+          Selectable: true
+          Size (Pixels): 3
+          Size (m): 0.00999999978
+          Style: Points
+          Topic: /ana/sensors/velodyne_points
+          Unreliable: false
+          Use Fixed Frame: true
+          Use rainbow: true
+          Value: true
       Enabled: true
-      Name: local_costmap
-      Topic: /move_base/local_costmap/costmap
-      Unreliable: false
-      Use Timestamp: false
-      Value: true
-    - Alpha: 1
-      Class: rviz/Polygon
-      Color: 25; 255; 0
+      Name: Sensors
+    - Class: rviz/Group
+      Displays:
+        - Alpha: 0.699999988
+          Class: rviz/Map
+          Color Scheme: map
+          Draw Behind: true
+          Enabled: true
+          Name: Map
+          Topic: /map
+          Unreliable: false
+          Use Timestamp: false
+          Value: true
+        - Alpha: 1
+          Class: rviz/Polygon
+          Color: 25; 255; 0
+          Enabled: true
+          Name: footprint
+          Topic: /move_base/global_costmap/footprint
+          Unreliable: false
+          Value: true
+        - Alpha: 0.699999988
+          Class: rviz/Map
+          Color Scheme: costmap
+          Draw Behind: true
+          Enabled: true
+          Name: local_costmap
+          Topic: /move_base/local_costmap/costmap
+          Unreliable: false
+          Use Timestamp: false
+          Value: true
+        - Alpha: 0.699999988
+          Class: rviz/Map
+          Color Scheme: costmap
+          Draw Behind: true
+          Enabled: true
+          Name: global_costmap
+          Topic: /move_base/global_costmap/costmap
+          Unreliable: false
+          Use Timestamp: false
+          Value: true
+        - Alpha: 1
+          Buffer Length: 1
+          Class: rviz/Path
+          Color: 0; 0; 255
+          Enabled: true
+          Head Diameter: 0.300000012
+          Head Length: 0.200000003
+          Length: 0.300000012
+          Line Style: Lines
+          Line Width: 0.0299999993
+          Name: global_plan
+          Offset:
+            X: 0
+            Y: 0
+            Z: 0
+          Pose Color: 255; 85; 255
+          Pose Style: None
+          Radius: 0.0299999993
+          Shaft Diameter: 0.100000001
+          Shaft Length: 0.100000001
+          Topic: /move_base/GlobalPlanner/plan
+          Unreliable: false
+          Value: true
+        - Alpha: 1
+          Buffer Length: 1
+          Class: rviz/Path
+          Color: 255; 0; 0
+          Enabled: true
+          Head Diameter: 0.300000012
+          Head Length: 0.200000003
+          Length: 0.300000012
+          Line Style: Lines
+          Line Width: 0.0299999993
+          Name: local_plan
+          Offset:
+            X: 0
+            Y: 0
+            Z: 0
+          Pose Color: 255; 85; 255
+          Pose Style: None
+          Radius: 0.0299999993
+          Shaft Diameter: 0.100000001
+          Shaft Length: 0.100000001
+          Topic: /move_base/DWAPlannerROS/local_plan
+          Unreliable: false
+          Value: true
+        - Alpha: 1
+          Axes Length: 1
+          Axes Radius: 0.100000001
+          Class: rviz/Pose
+          Color: 255; 255; 0
+          Enabled: true
+          Head Length: 0.300000012
+          Head Radius: 0.100000001
+          Name: CurrentGoal
+          Shaft Length: 1
+          Shaft Radius: 0.0500000007
+          Shape: Arrow
+          Topic: /move_base/current_goal
+          Unreliable: false
+          Value: true
       Enabled: true
-      Name: footprint
-      Topic: /move_base/global_costmap/footprint
-      Unreliable: false
-      Value: true
+      Name: Nav
   Enabled: true
   Global Options:
     Background Color: 48; 48; 48
@@ -518,25 +552,25 @@ Visualization Manager:
   Views:
     Current:
       Class: rviz/Orbit
-      Distance: 8.14016628
+      Distance: 10
       Enable Stereo Rendering:
         Stereo Eye Separation: 0.0599999987
         Stereo Focal Distance: 1
         Swap Stereo Eyes: false
         Value: false
       Focal Point:
-        X: 0.296762884
-        Y: -0.0358628929
-        Z: -0.184484214
-      Focal Shape Fixed Size: true
+        X: 0
+        Y: 0
+        Z: 0
+      Focal Shape Fixed Size: false
       Focal Shape Size: 0.0500000007
       Invert Z Axis: false
       Name: Current View
       Near Clip Distance: 0.00999999978
-      Pitch: 1.1903975
-      Target Frame: <Fixed Frame>
+      Pitch: 0.785398185
+      Target Frame: ana/base_footprint
       Value: Orbit (rviz)
-      Yaw: 1.23039782
+      Yaw: 0.785398185
     Saved: ~
 Window Geometry:
   Displays:
@@ -544,7 +578,7 @@ Window Geometry:
   Height: 1056
   Hide Left Dock: false
   Hide Right Dock: false
-  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000299000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e007200650061006c00730065006e00730065005f0063006f006c006f007201000002c7000000f70000001600ffffff000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000396000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004ba0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a000003dafc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002b0000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e007200650061006c00730065006e00730065005f0063006f006c006f007201000002de000001240000001600ffffff000000010000010f000003dafc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000003da000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf000003da00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
   Selection:
     collapsed: false
   Time:
-- 
GitLab