diff --git a/launch/3d_nav_map.launch b/launch/3d_nav_map.launch
new file mode 100644
index 0000000000000000000000000000000000000000..73af9f844ad0eb60865741cfbbe45a22500a3463
--- /dev/null
+++ b/launch/3d_nav_map.launch
@@ -0,0 +1,51 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="name"                    default="helena"/>
+
+  <arg name="use_3d_nav_nodelets"     default="true"/>
+
+  <arg name="path"                    default="$(find iri_helena_rosnav)/params"/>
+  <arg name="move_base_params"        default="move_base_params.yaml"/>
+  <arg name="costmap_common_params"   default="common_params.yaml"/>
+  <arg name="costmap_local_params"    default="local_params.yaml"/>
+  <arg name="costmap_global_params"   default="global_params.yaml"/>
+  <arg name="map_path"                default="$(find iri_maps)/maps"/>
+  <arg name="map_name"                default="empty" />
+  <arg name="initial_x"               default="0.0"/>
+  <arg name="initial_y"               default="0.0"/>
+  <arg name="initial_yaw"             default="0.0"/>
+  <arg name="use_move_base"           default="true"/>
+  <arg name="local_planner"           default="dwa"/>
+  <arg name="global_planner"          default="global_planner"/>
+
+  <arg name="rviz"                    default="true"/>
+  <arg name="rviz_file"               default="$(find iri_helena_rosnav)/rviz/3d_helena.rviz"/>
+
+  <arg name="output"                  default="screen"/>
+  <arg name="launch_prefix"           default=""/>
+
+  <include file="$(find iri_helena_rosnav)/launch/include/3d_nav.launch">
+    <arg name="output"        value="$(arg output)"/>
+    <arg name="launch_prefix" value="$(arg launch_prefix)"/>
+    <arg name="use_nodelets"  value="$(arg use_3d_nav_nodelets)"/>
+  </include>
+
+  <include file="$(find iri_helena_rosnav)/launch/nav_map.launch">
+    <arg name="name"                  value="$(arg name)"/>
+    <arg name="rviz"                  value="$(arg rviz)"/>
+    <arg name="rviz_file"             value="$(arg rviz_file)"/>
+    <arg name="move_base_params"      value="$(arg move_base_params)"/>
+    <arg name="costmap_common_params" value="$(arg costmap_common_params)"/>
+    <arg name="costmap_local_params"  value="$(arg costmap_local_params)"/>
+    <arg name="costmap_global_params" value="$(arg costmap_global_params)"/>
+    <arg name="map_name"              value="$(arg map_name)"/>
+    <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="local_planner"         value="$(arg local_planner)"/>
+    <arg name="global_planner"        value="$(arg global_planner)"/>
+  </include>
+
+</launch>
diff --git a/launch/3d_nav_nomap.launch b/launch/3d_nav_nomap.launch
new file mode 100644
index 0000000000000000000000000000000000000000..2d5f74078bf8a9ee9958de933528bb87f36366be
--- /dev/null
+++ b/launch/3d_nav_nomap.launch
@@ -0,0 +1,50 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+
+  <arg name="name"                    default="helena"/>
+
+  <arg name="use_3d_nav_nodelets"     default="true"/>
+
+  <arg name="path"                    default="$(find iri_helena_rosnav)/params"/>
+  <arg name="move_base_params"        default="move_base_params.yaml"/>
+  <arg name="costmap_common_params"   default="common_params.yaml"/>
+  <arg name="costmap_local_params"    default="local_params.yaml"/>
+  <arg name="costmap_global_params"   default="global_params.yaml"/>
+  <arg name="map_path"                default="$(find iri_maps)/maps"/>
+  <!--<arg name="map_name"                default="empty" />-->
+  <arg name="initial_x"               default="0.0"/>
+  <arg name="initial_y"               default="0.0"/>
+  <arg name="initial_yaw"             default="0.0"/>
+  <arg name="use_move_base"           default="true"/>
+  <arg name="local_planner"           default="dwa"/>
+  <arg name="global_planner"          default="global_planner"/>
+
+  <arg name="rviz"                    default="true"/>
+  <arg name="rviz_file"               default="$(find iri_helena_rosnav)/rviz/3d_helena.rviz"/>
+
+  <arg name="output"                  default="screen"/>
+  <arg name="launch_prefix"           default=""/>
+
+  <include file="$(find iri_helena_rosnav)/launch/include/3d_nav.launch">
+    <arg name="output"        value="$(arg output)"/>
+    <arg name="launch_prefix" value="$(arg launch_prefix)"/>
+    <arg name="use_nodelets"  value="$(arg use_3d_nav_nodelets)"/>
+  </include>
+
+  <include file="$(find iri_helena_rosnav)/launch/nav_nomap.launch">
+    <arg name="name"                  value="$(arg name)"/>
+    <arg name="rviz"                  value="$(arg rviz)"/>
+    <arg name="rviz_file"             value="$(arg rviz_file)"/>
+    <arg name="move_base_params"      value="$(arg move_base_params)"/>
+    <arg name="costmap_common_params" value="$(arg costmap_common_params)"/>
+    <arg name="costmap_local_params"  value="$(arg costmap_local_params)"/>
+    <arg name="costmap_global_params" value="$(arg costmap_global_params)"/>
+    <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="local_planner"         value="$(arg local_planner)"/>
+    <arg name="global_planner"        value="$(arg global_planner)"/>
+  </include>
+
+</launch>
diff --git a/launch/include/3d_nav.launch b/launch/include/3d_nav.launch
new file mode 100644
index 0000000000000000000000000000000000000000..98ac77c85a05bf7af7a034f7ed1fd1189a284047
--- /dev/null
+++ b/launch/include/3d_nav.launch
@@ -0,0 +1,42 @@
+<?xml version="1.0"?>
+<!-- -->
+<launch>
+ 
+  <arg name="output" default="screen"/>
+  <arg name="launch_prefix" default=""/>
+  <arg name="use_nodelets" default="true"/>
+
+  <include file="$(find iri_rosnav)/launch/include/3d_nav_lidar.launch">
+    <arg name="ns" value="helena"/>
+    <arg name="output" value="$(arg output)"/>
+    <arg name="launch_prefix" value="$(arg launch_prefix)"/>
+    <arg name="use_nodelets" value="$(arg use_nodelets)"/>
+    <arg name="lidar_nodelet_manager" value="lidar_nodelet_manager"/>
+    <arg name="lidar_filter_node_name" value="lidar_filter"/>
+    <arg name="lidar_filter_config_file" value="$(find iri_point_cloud_angle_filter)/config/default_config.yaml"/>
+    <arg name="lidar_filter_cloud_in" value="/helena/sensors/rslidar_points" />
+    <arg name="lidar_detector_node_name" value="lidar_detector"/>
+    <arg name="lidar_detector_config_file" value="$(find iri_lidar_obstacle_detector)/config/default_config.yaml"/>
+  </include>
+
+  <include file="$(find iri_rosnav)/launch/include/3d_nav_camera.launch">
+    <arg name="ns" value="helena"/>
+    <arg name="output" value="$(arg output)"/>
+    <arg name="launch_prefix" value="$(arg launch_prefix)"/>
+    <arg name="use_nodelets" value="$(arg use_nodelets)"/>
+    <arg name="obstacle_nodelet_manager" value="obstacle_nodelet_manager" />
+    <arg name="hole_nodelet_manager" value="hole_nodelet_manager" />
+    <arg name="camera_cloud_in" value="sensors/nav_cam/depth_registered/points"/>
+    <arg name="average_node_name" value="average_point_cloud"/>
+    <arg name="average_config_file" value="$(find iri_average_point_cloud)/config/default_config.yaml"/>
+    <arg name="normals_node_name" value="obstacle_detection_normals"/>
+    <arg name="normals_config_file" value="$(find iri_nav_obstacle_detection_normals)/config/default_config.yaml"/>
+    <arg name="near_hole_detection_node_name" value="near_hole_detection"/>
+    <arg name="near_hole_detection_config_file" value="$(find iri_point_cloud_hole_detection)/config/near_config.yaml"/>
+    <arg name="hole_detection_cloud_in" value="radius_outlier_removal/output"/>
+    <arg name="far_hole_detection_node_name" value="far_hole_detection"/>
+    <arg name="far_hole_detection_config_file" value="$(find iri_point_cloud_hole_detection)/config/far_config.yaml"/>
+  </include>
+
+</launch>
+
diff --git a/launch/nav_map.launch b/launch/nav_map.launch
index 5353c3d71d87eeb23a78d115b41770c9b90e4b7a..bfb2662113a55f89bcecafa0e060348f22842fd5 100644
--- a/launch/nav_map.launch
+++ b/launch/nav_map.launch
@@ -1,88 +1,76 @@
 <?xml version="1.0"?>
 <!-- -->
 <launch>
-
-  <arg name="rviz"           default="true"/>
-  <arg name="ns"             default="helena"/>
-  <arg name="pkg"            default="iri_helena_rosnav"/>
-    <arg name="path"         default="$(eval find(arg('pkg')))"/>
-  <arg name="param_subpath" default="params"/>
-  <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)/sensors/scan"/>
-  <arg name="use_map"        default="true"/>
-  <arg name="use_map_server" default="true"/>
-    <arg name="map_name"      />
-  <arg name="use_amcl"       default="true"/>
-    <arg name="amcl_config"    default="$(arg path)/$(arg param_subpath)/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)/sensors/scan"/>
-    <arg name="gmapping_config"     default="$(arg path)/$(arg param_subpath)/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)/$(arg param_subpath)/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="" />
+  <arg name="name"                    default="helena"/>
+  <arg name="path"                    default="$(find iri_helena_rosnav)/params"/>
+    <arg name="move_base_params"        default="move_base_params.yaml"/>
+    <arg name="costmap_common_params"   default="common_params.yaml"/>
+    <arg name="costmap_local_params"    default="local_params.yaml"/>
+    <arg name="costmap_global_params"   default="global_params.yaml"/>
+  <arg name="map_path"                default="$(find iri_maps)/maps"/>
+  <arg name="map_name"                default="empty" />
+  <arg name="initial_x"               default="0.0"/>
+  <arg name="initial_y"               default="0.0"/>
+  <arg name="initial_yaw"             default="0.0"/>
+  <arg name="use_move_base"           default="true"/>
+    <arg name="local_planner"           default="dwa"/>
+    <arg name="global_planner"          default="global_planner"/>
+  <arg name="rviz"                    default="true"/>
+  <arg name="rviz_file"               default="$(find iri_helena_rosnav)/rviz/helena.rviz"/>
+  <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="param_subpath"  value="$(arg param_subpath)"/>
-    <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"        value="$(arg use_map)"/>
-    <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)" />
+    <arg name="ns"                    value="$(arg name)"/>
+    <arg name="path"                  value="$(arg path)"/>
+    <arg name="move_base_params"      value="$(arg move_base_params)"/>
+    <arg name="costmap_common_params" value="$(arg costmap_common_params)"/>
+    <arg name="costmap_local_params"  value="$(arg costmap_local_params)"/>
+    <arg name="costmap_global_params" value="$(arg costmap_global_params)"/>
+    <arg name="map_frame_id"          value="map"/>
+    <arg name="odom_frame_id"         value="$(arg name)/odom"/>
+    <arg name="base_frame_id"         value="$(arg name)/base_footprint"/>
+    <arg name="map_topic"             value="/$(arg name)/map"/>
+    <arg name="map_service"           value="/$(arg name)/static_map"/>
+    <arg name="odom_topic"            value="/$(arg name)/odom"/>
+    <arg name="cmd_vel_topic"         value="/$(arg name)/navigation/cmd_vel"/>
+    <arg name="scan_topic"            value="/$(arg name)/sensors/scan"/>
+    <arg name="use_map"               value="true"/>
+    <arg name="use_map_server"        value="true"/>
+    <arg name="map_path"              value="$(arg map_path)"/>
+    <arg name="map_name"              value="$(arg map_name)"/>
+    <arg name="use_amcl"              value="true"/>
+    <arg name="amcl_config"           value="$(find iri_helena_rosnav)/params/amcl.yaml"/>
+    <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="false"/>
+    <arg name="use_gmapping"          value="false"/>
+    <arg name="gmapping_scan_topic"   value="/$(arg name)/sensors/scan"/>
+    <arg name="gmapping_config"       value="$(arg path)/gmapping.yaml"/>
+    <arg name="resolution"            value="0.1"/>
+    <arg name="use_move_base"         value="$(arg use_move_base)"/>
+    <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="$(find iri_rosnav)/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/rslidar_points"/>
+    <arg name="ns"             value="helena"/>
+    <arg name="node_name"      value="pcl_to_laserscan"/>
+    <arg name="scan_topic"     value="/$(arg name)/sensors/scan"/>
+    <arg name="cloud_topic"    value="/$(arg name)/sensors/rslidar_points"/>
+    <arg name="config_file"    value="$(find iri_helena_rosnav)/params/pointcloud_to_laserscan.yaml" />
     <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">
+        args="-d $(arg rviz_file)">
   </node>
 
 </launch>
diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch
index 5857d9b388a782eb1d3487f6120770a1c3e614a5..e855b6a2fef55235a4415a87a7656c604b6997d3 100644
--- a/launch/nav_mapping.launch
+++ b/launch/nav_mapping.launch
@@ -5,8 +5,7 @@
   <arg name="rviz"           default="true"/>
   <arg name="ns"             default="helena"/>
   <arg name="pkg"            default="iri_helena_rosnav"/>
-    <arg name="path"         default="$(eval find(arg('pkg')))"/>
-  <arg name="param_subpath"  default="params"/>
+    <arg name="path"           default="$(eval find(arg('pkg')))_lolo"/>
   <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"/>
diff --git a/launch/nav_nomap.launch b/launch/nav_nomap.launch
index cc75c1efdb2f13542ef89474895bbb81a89904a8..ff3b991036becc5ddf12dfd9c06d984510c9d205 100644
--- a/launch/nav_nomap.launch
+++ b/launch/nav_nomap.launch
@@ -1,88 +1,76 @@
 <?xml version="1.0"?>
 <!-- -->
 <launch>
-
-  <arg name="rviz"           default="true"/>
-  <arg name="ns"             default="helena"/>
-  <arg name="pkg"            default="iri_helena_rosnav"/>
-    <arg name="path"         default="$(eval find(arg('pkg')))"/>
-  <arg name="param_subpath" default="params"/>
-  <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)/sensors/scan"/>
-  <arg name="use_map"        default="false"/>
-  <arg name="use_map_server" default="false"/>
-    <arg name="map_name"       default="empty"/>
-  <arg name="use_amcl"       default="false"/>
-    <arg name="amcl_config"    default="$(arg path)/$(arg param_subpath)/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)/sensors/scan"/>
-    <arg name="gmapping_config"     default="$(arg path)/$(arg param_subpath)/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)/$(arg param_subpath)/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="" />
+  <arg name="name"                    default="helena"/>
+  <arg name="path"                    default="$(find iri_helena_rosnav)/params"/>
+    <arg name="move_base_params"        default="move_base_params.yaml"/>
+    <arg name="costmap_common_params"   default="common_params.yaml"/>
+    <arg name="costmap_local_params"    default="local_params.yaml"/>
+    <arg name="costmap_global_params"   default="global_params.yaml"/>
+  <arg name="map_path"                default="$(find iri_maps)/maps"/>
+  <arg name="map_name"                default="empty" />
+  <arg name="initial_x"               default="0.0"/>
+  <arg name="initial_y"               default="0.0"/>
+  <arg name="initial_yaw"             default="0.0"/>
+  <arg name="use_move_base"           default="true"/>
+    <arg name="local_planner"           default="dwa"/>
+    <arg name="global_planner"          default="global_planner"/>
+  <arg name="rviz"                    default="true"/>
+  <arg name="rviz_file"               default="$(find iri_helena_rosnav)/rviz/helena.rviz"/>
+  <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="param_subpath"  value="$(arg param_subpath)"/>
-    <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"        value="$(arg use_map)"/>
-    <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)" />
+    <arg name="ns"                    value="$(arg name)"/>
+    <arg name="path"                  value="$(arg path)"/>
+    <arg name="move_base_params"      value="$(arg move_base_params)"/>
+    <arg name="costmap_common_params" value="$(arg costmap_common_params)"/>
+    <arg name="costmap_local_params"  value="$(arg costmap_local_params)"/>
+    <arg name="costmap_global_params" value="$(arg costmap_global_params)"/>
+    <arg name="map_frame_id"          value="map"/>
+    <arg name="odom_frame_id"         value="$(arg name)/odom"/>
+    <arg name="base_frame_id"         value="$(arg name)/base_footprint"/>
+    <arg name="map_topic"             value="/$(arg name)/map"/>
+    <arg name="map_service"           value="/$(arg name)/static_map"/>
+    <arg name="odom_topic"            value="/$(arg name)/odom"/>
+    <arg name="cmd_vel_topic"         value="/$(arg name)/navigation/cmd_vel"/>
+    <arg name="scan_topic"            value="/$(arg name)/sensors/scan"/>
+    <arg name="use_map"               value="false"/>
+    <arg name="use_map_server"        value="true"/>
+    <arg name="map_path"              value="$(arg map_path)"/>
+    <arg name="map_name"              value="$(arg map_name)"/>
+    <arg name="use_amcl"              value="true"/>
+    <arg name="amcl_config"           value="$(find iri_helena_rosnav)/params/amcl.yaml"/>
+    <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="false"/>
+    <arg name="use_gmapping"          value="false"/>
+    <arg name="gmapping_scan_topic"   value="/$(arg name)/sensors/scan"/>
+    <arg name="gmapping_config"       value="$(arg path)/gmapping.yaml"/>
+    <arg name="resolution"            value="0.1"/>
+    <arg name="use_move_base"         value="$(arg use_move_base)"/>
+    <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="$(find iri_rosnav)/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/rslidar_points"/>
+    <arg name="ns"             value="helena"/>
+    <arg name="node_name"      value="pcl_to_laserscan"/>
+    <arg name="scan_topic"     value="/$(arg name)/sensors/scan"/>
+    <arg name="cloud_topic"    value="/$(arg name)/sensors/rslidar_points"/>
+    <arg name="config_file"    value="$(find iri_helena_rosnav)/params/pointcloud_to_laserscan.yaml" />
     <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">
+        args="-d $(arg rviz_file)">
   </node>
 
 </launch>
diff --git a/params/costmap/3d_common_params.yaml b/params/costmap/3d_common_params.yaml
new file mode 100755
index 0000000000000000000000000000000000000000..e0c534f6e826965cd0b6c804d115e1c563dfb801
--- /dev/null
+++ b/params/costmap/3d_common_params.yaml
@@ -0,0 +1,142 @@
+# footprint parameters
+footprint: [[0.3, 0.3], [0.3, -0.3], [-0.3,-0.3 ], [-0.3, 0.3]]
+#robot_radius: 0.3
+footprint_padding: 0.01
+footprint_topic: /helena/footprint
+published_footprint_topic: false
+
+robot_base_frame: helena/base_footprint
+track_unknown_space: false
+always_send_full_costmap: false
+transform_tolerance: 1.0
+width: 10.0
+height: 10.0
+resolution: 0.1
+origin_x: 0.0
+origin_y: 0.0
+
+obstacle_layer_lidar:
+  enabled: true
+  track_unknown_space: true
+  transform_tolerance: 0.2
+  max_obstacle_height: 10.0
+  footprint_clearing_enabled: false
+  combination_method: 1 
+  observation_sources:  lidar_marking
+  lidar_marking: {
+    sensor_frame: helena/base_footprint,
+    data_type: LaserScan,
+    topic: /helena/lidar_detector/scan_out,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: true,
+    min_obstacle_height: -10.0,
+    max_obstacle_height: 10.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 200.0
+  }
+
+obstacle_layer_camera:
+  enabled: true
+  track_unknown_space: true
+  transform_tolerance: 0.2
+  max_obstacle_height: 100.0 #1.0
+  footprint_clearing_enabled: false
+  combination_method: 1
+  observation_sources:  camera_marking
+
+  camera_marking: {
+    sensor_frame: helena/base_footprint,
+    data_type: PointCloud,
+    topic: /helena/obstacle_detection_normals/obstacles,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: true,
+    min_obstacle_height: -100.0,
+    max_obstacle_height: 100.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 10.0
+  }
+
+hole_layer_near_camera:
+  enabled: true
+  track_unknown_space: true
+  transform_tolerance: 0.2
+  max_obstacle_height: 100.0 #1.0
+  footprint_clearing_enabled: false
+  combination_method: 1
+  observation_sources: hole_near_marking hole_near_clearing
+
+  hole_near_marking: {
+    sensor_frame: helena/base_footprint,
+    data_type: PointCloud2,
+    topic: /helena/near_hole_detection/hole_obstacle,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: false,
+    min_obstacle_height: -100.0,
+    max_obstacle_height: 100.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 10.0
+  }
+
+  hole_near_clearing: {
+    sensor_frame: helena/base_footprint,
+    data_type: PointCloud2,
+    topic: /helena/near_hole_detection/hole_zone,
+    observation_persistence: 0.0,
+    marking: false,
+    clearing: true,
+    min_obstacle_height: -100.0,
+    max_obstacle_height: 100.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 10.0
+  }
+
+hole_layer_far_camera:
+  enabled: true
+  track_unknown_space: true
+  transform_tolerance: 0.2
+  max_obstacle_height: 100.0 #1.0
+  footprint_clearing_enabled: false
+  combination_method: 1
+  observation_sources: hole_far_marking hole_far_clearing
+
+  hole_far_marking: {
+    sensor_frame: helena/base_footprint,
+    data_type: PointCloud2,
+    topic: /helena/far_hole_detection/hole_obstacle,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: false,
+    min_obstacle_height: -100.0,
+    max_obstacle_height: 100.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 10.0
+  }
+
+  hole_far_clearing: {
+    sensor_frame: helena/base_footprint,
+    data_type: PointCloud2,
+    topic: /helena/far_hole_detection/hole_zone,
+    observation_persistence: 0.0,
+    marking: false,
+    clearing: true,
+    min_obstacle_height: -100.0,
+    max_obstacle_height: 100.0,
+    expected_update_rate: 1,
+    obstacle_range: 5.0,
+    raytrace_range: 10.0
+  }
+
+inflation_layer:
+  enabled: true
+  inflate_unknown: false
+  inflation_radius: 2.0
+  cost_scaling_factor:  1.8
+  inflation_radius:     1.0
diff --git a/params/costmap/3d_local_params.yaml b/params/costmap/3d_local_params.yaml
new file mode 100755
index 0000000000000000000000000000000000000000..54d160e0e86fd02dd7e4b1c2937ed55a607fd630
--- /dev/null
+++ b/params/costmap/3d_local_params.yaml
@@ -0,0 +1,20 @@
+#local_costmap:  ###namespace added when loading parameters in move_base.launch
+global_frame: helena/odom
+update_frequency: 5.0
+publish_frequency: 2.0
+rolling_window: true
+width: 10.0
+height: 10.0
+resolution: 0.1
+#origin_x: 0.0
+#origin_y: 0.0
+
+#costmap plugins
+plugins:
+ - {name: obstacle_layer_lidar,   type: "costmap_2d::ObstacleLayer"}
+ - {name: obstacle_layer_camera,  type: "costmap_2d::ObstacleLayer"}
+ - {name: hole_layer_near_camera, type: "costmap_2d::ObstacleLayer"}
+ - {name: hole_layer_far_camera,  type: "costmap_2d::ObstacleLayer"}
+ - {name: inflation_layer,        type: "costmap_2d::InflationLayer"}
+
+
diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml
index 69db1eb705d94017802732bf286f940a240acf5a..d3ab3718f15a4999c0b8b062f57bb873908721cb 100644
--- a/params/costmap/common_params.yaml
+++ b/params/costmap/common_params.yaml
@@ -5,7 +5,7 @@ footprint_padding: 0.01
 footprint_topic: /helena/move_base/local_costmap/footprint
 published_footprint_topic: false
 
-robot_base_frame: /helena/base_footprint
+robot_base_frame: helena/base_footprint
 track_unknown_space: false
 always_send_full_costmap: false
 transform_tolerance: 1.0
@@ -25,7 +25,7 @@ obstacle_layer:
   observation_sources: velodyne #depth_cam
   
   velodyne:  {
-    sensor_frame: /helena/robosense,
+    sensor_frame: helena/robosense,
     data_type: PointCloud2,
     topic: /helena/sensors/rslidar_points,
     observation_persistence: 0.0,
@@ -39,7 +39,7 @@ obstacle_layer:
   }
   
   depth_cam:  {
-    sensor_frame: /helena/camera_color_optical_frame,
+    sensor_frame: helena/camera_color_optical_frame,
     data_type: PointCloud2,
     topic: /helena/sensors/nav_cam/depth_registered/points,
     observation_persistence: 0.0,
diff --git a/params/costmap/local_params.yaml b/params/costmap/local_params.yaml
index a6f1022fde2c6bf2bd0d4adcda40e34331bc453c..330c2f87e7caa206a8d778cc0559ffb7510d7d04 100644
--- a/params/costmap/local_params.yaml
+++ b/params/costmap/local_params.yaml
@@ -1,5 +1,5 @@
 #local_costmap:  ###namespace added when loading parameters in move_base.launch
-global_frame: /helena/odom
+global_frame: helena/odom
 update_frequency: 5.0
 publish_frequency: 2.0
 rolling_window: true
@@ -12,4 +12,4 @@ origin_y: 0.0
 #costmap plugins
 plugins:
   - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
-  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
\ No newline at end of file
+  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
diff --git a/params/costmap/map/3d_global_params.yaml b/params/costmap/map/3d_global_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..09fc474b71a4643b2f55a495eaafb61aac8b4b61
--- /dev/null
+++ b/params/costmap/map/3d_global_params.yaml
@@ -0,0 +1,24 @@
+#global_costmap: ###namespace added when loading parameters in move_base.launch
+global_frame: map
+update_frequency: 1.0
+publish_frequency: 1.0
+rolling_window: false
+
+plugins:
+  - {name: static_layer,          type: "costmap_2d::StaticLayer"}
+  - {name: obstacle_layer_lidar,  type: "costmap_2d::ObstacleLayer"}
+  - {name: obstacle_layer_camera, type: "costmap_2d::ObstacleLayer"}
+  - {name: hole_layer_near_camera,type: "costmap_2d::ObstacleLayer"}
+  - {name: hole_layer_far_camera, type: "costmap_2d::ObstacleLayer"}
+  - {name: inflation_layer,       type: "costmap_2d::InflationLayer"}
+    
+static_layer:
+  enabled: true
+  map_topic: /map
+  first_map_only: false
+  subscribe_to_updates: false
+  unknown_cost_value: -1
+  use_maximum: false
+  lethal_cost_threshold: 100
+  track_unknown_space: true
+  trinary_costmap: true
diff --git a/params/costmap/map/global_params.yaml b/params/costmap/map/global_params.yaml
index aef60d4da3e1ae19918181efd4328115bd1283bf..1df7af232c4f0ddfcda8bea87bf25bb9417a2885 100644
--- a/params/costmap/map/global_params.yaml
+++ b/params/costmap/map/global_params.yaml
@@ -1,5 +1,5 @@
 #global_costmap: ###namespace added when loading parameters in move_base.launch
-global_frame: /map
+global_frame: map
 update_frequency: 1.0
 publish_frequency: 0.0
 rolling_window: false
@@ -18,4 +18,4 @@ static_layer:
   use_maximum: false
   lethal_cost_threshold: 100
   track_unknown_space: true
-  trinary_costmap: true
\ No newline at end of file
+  trinary_costmap: true
diff --git a/params/costmap/no_map/3d_global_params.yaml b/params/costmap/no_map/3d_global_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..279a9c254d6fe6198b05afb88a590b2d23127008
--- /dev/null
+++ b/params/costmap/no_map/3d_global_params.yaml
@@ -0,0 +1,18 @@
+#global_costmap: ###namespace added when loading parameters in move_base.launch
+global_frame: helena/odom
+update_frequency: 1.0
+publish_frequency: 0.0
+rolling_window: true
+transform_tolerance: 1.0
+width: 20.0
+height: 20.0
+resolution: 0.2
+origin_x: 0.0
+origin_y: 0.0
+
+plugins:
+  - {name: obstacle_layer_lidar,   type: "costmap_2d::ObstacleLayer"}
+  - {name: obstacle_layer_camera,  type: "costmap_2d::ObstacleLayer"}
+  - {name: hole_layer_near_camera, type: "costmap_2d::ObstacleLayer"}
+  - {name: hole_layer_far_camera,  type: "costmap_2d::ObstacleLayer"}
+  - {name: inflation_layer,        type: "costmap_2d::InflationLayer"}
diff --git a/params/costmap/no_map/global_params.yaml b/params/costmap/no_map/global_params.yaml
index f85664cbbfe472799aac674fa78325e6d96a59e0..389e95e90cdfb2685e93e416dfd8fe0fe324a810 100644
--- a/params/costmap/no_map/global_params.yaml
+++ b/params/costmap/no_map/global_params.yaml
@@ -1,5 +1,5 @@
 #global_costmap: ###namespace added when loading parameters in move_base.launch
-global_frame: /helena/odom
+global_frame: helena/odom
 update_frequency: 1.0
 publish_frequency: 0.0
 rolling_window: true
@@ -12,4 +12,4 @@ origin_y: 0.0
 
 plugins:
   - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
-  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
\ No newline at end of file
+  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml
index d6e7bb71e11320c65a66559b2745d42e90a27c49..482726a1d9813d7e2f3441bb1dc53dde4295c89d 100644
--- a/params/local_planner/dwa_params.yaml
+++ b/params/local_planner/dwa_params.yaml
@@ -1,40 +1,40 @@
 base_local_planner: "dwa_local_planner/DWAPlannerROS"
-latch_xy_goal_tolerance: true 
+latch_xy_goal_tolerance: true
 
 DWAPlannerROS:
 # robot configuration parameters
-  max_trans_vel: 0.5
-  min_trans_vel: 0.1
+  max_vel_trans: 0.5
+  min_vel_trans: 0.1
   max_vel_x: 0.5
-  min_vel_x: -0.2
-  max_vel_y: 0.0 
-  min_vel_y: 0.0 
-  max_rot_vel: 2.0
-  min_rot_vel: 0.2 
+  min_vel_x: 0.0
+  max_vel_y: 0.0
+  min_vel_y: 0.0
+  max_vel_theta: 2.0
+  min_vel_theta: 0.1
   acc_lim_theta: 5.0
   acc_lim_x: 1.0
-  acc_lim_y: 0.0 
-  acc_limit_trans: 1.0
-  rot_stopped_vel: 0.1
+  acc_lim_y: 0.0
+  acc_lim_trans: 1.0
+  theta_stopped_vel: 0.1
   trans_stopped_vel: 0.1
 
 # goal tolerance parameters
-  xy_goal_tolerance: 0.1 
-  yaw_goal_tolerance: 0.1 
+  xy_goal_tolerance: 0.1
+  yaw_goal_tolerance: 0.1
 
 # Forward simulation parameters
-  sim_time: 2.5
+  sim_time: 3.5
   sim_granularity: 0.1
   angular_sim_granularity: 0.1
   vx_samples: 21
-  vy_samples: 1 
+  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: 24.0
-  occdist_scale: 0.02 #0.01
+  path_distance_bias: 50.0
+  goal_distance_bias: 10.0
+  occdist_scale: 0.05
   twirling_scale: 0.0
   stop_time_buffer: 0.2
   forward_point_distance: 0.325
@@ -44,11 +44,11 @@ DWAPlannerROS:
 # 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
-  global_frame_id: /helena/odom
+  #global_frame_id: /robot/base_footprint
   publish_cost_grid_pc: false
diff --git a/params/pointcloud_to_laserscan.yaml b/params/pointcloud_to_laserscan.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..120eb90529316fad34fa03874c46fad29c8e51e7
--- /dev/null
+++ b/params/pointcloud_to_laserscan.yaml
@@ -0,0 +1,18 @@
+target_frame: ""
+# Leave target_frame disabled to output scan in pointcloud frame
+transform_tolerance: 0.1
+min_height: -0.1
+max_height: 0.5
+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
diff --git a/rviz/3d_helena.rviz b/rviz/3d_helena.rviz
new file mode 100644
index 0000000000000000000000000000000000000000..f1ca519729f7bdb4b54eb03e78be8a867c5b130a
--- /dev/null
+++ b/rviz/3d_helena.rviz
@@ -0,0 +1,1068 @@
+Panels:
+  - Class: rviz/Displays
+    Help Height: 78
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /TF1/Frames1
+        - /Nav1
+        - /3d_nav_detection1
+        - /3d_nav_detection1/lidar1
+        - /3d_nav_detection1/camera1
+      Splitter Ratio: 0.548672557
+    Tree Height: 693
+  - Class: rviz/Selection
+    Name: Selection
+  - Class: rviz/Tool Properties
+    Expanded:
+      - /2D Pose Estimate1
+      - /2D Nav Goal1
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.588679016
+  - Class: rviz/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: rviz/Time
+    Experimental: false
+    Name: Time
+    SyncMode: 0
+    SyncSource: lidar_obstacle
+  - Class: rviz_plugin_tutorials/Teleop
+    Name: Teleop
+    Topic: ""
+Toolbars:
+  toolButtonStyle: 2
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz/Grid
+      Color: 160; 160; 164
+      Enabled: true
+      Line Style:
+        Line Width: 0.0299999993
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 1000
+      Reference Frame: <Fixed Frame>
+      Value: true
+    - Alpha: 1
+      Class: rviz/RobotModel
+      Collision Enabled: false
+      Enabled: true
+      Links:
+        All Links Enabled: true
+        Expand Joint Details: false
+        Expand Link Details: false
+        Expand Tree: false
+        Link Tree Style: Links in Alphabetic Order
+        helena_box:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        helena_realsense_support:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        base_footprint:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        base_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        camera_bottom_screw_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_color_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_color_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_depth_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_depth_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_infra1_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_infra1_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_infra2_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_infra2_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        camera_pan_tilt_bottom_screw_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_color_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_color_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_depth_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_depth_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_infra1_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_infra1_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_infra2_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_infra2_optical_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        camera_pan_tilt_link:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_left_axle:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_left_hub:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_left_wheel:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_right_axle:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_right_hub:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_right_wheel:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        front_sonar:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        imu_bno055:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        imu_bno055_base:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        pan_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        realsense_support_pan_tilt:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+        rear_left_axle:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_left_hub:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_left_wheel:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_right_axle:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_right_hub:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_right_wheel:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        rear_sonar:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        tilt_frame:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        top_plate:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        velodyne:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        velodyne_base:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+      Name: RobotModel
+      Robot Description: helena/robot_description
+      TF Prefix: helena
+      Update Interval: 0
+      Value: true
+      Visual Enabled: true
+    - Class: rviz/TF
+      Enabled: true
+      Frame Timeout: 15
+      Frames:
+        All Enabled: true
+        helena/helena_box:
+          Value: true
+        helena/helena_realsense_support:
+          Value: true
+        helena/base_footprint:
+          Value: true
+        helena/base_link:
+          Value: true
+        helena/camera_bottom_screw_frame:
+          Value: true
+        helena/camera_color_frame:
+          Value: true
+        helena/camera_color_optical_frame:
+          Value: true
+        helena/camera_depth_frame:
+          Value: true
+        helena/camera_depth_optical_frame:
+          Value: true
+        helena/camera_infra1_frame:
+          Value: true
+        helena/camera_infra1_optical_frame:
+          Value: true
+        helena/camera_infra2_frame:
+          Value: true
+        helena/camera_infra2_optical_frame:
+          Value: true
+        helena/camera_link:
+          Value: true
+        helena/camera_pan_tilt_bottom_screw_frame:
+          Value: true
+        helena/camera_pan_tilt_color_frame:
+          Value: true
+        helena/camera_pan_tilt_color_optical_frame:
+          Value: true
+        helena/camera_pan_tilt_depth_frame:
+          Value: true
+        helena/camera_pan_tilt_depth_optical_frame:
+          Value: true
+        helena/camera_pan_tilt_infra1_frame:
+          Value: true
+        helena/camera_pan_tilt_infra1_optical_frame:
+          Value: true
+        helena/camera_pan_tilt_infra2_frame:
+          Value: true
+        helena/camera_pan_tilt_infra2_optical_frame:
+          Value: true
+        helena/camera_pan_tilt_link:
+          Value: true
+        helena/front_left_axle:
+          Value: true
+        helena/front_left_hub:
+          Value: true
+        helena/front_left_wheel:
+          Value: true
+        helena/front_right_axle:
+          Value: true
+        helena/front_right_hub:
+          Value: true
+        helena/front_right_wheel:
+          Value: true
+        helena/front_sonar:
+          Value: true
+        helena/imu_bno055:
+          Value: true
+        helena/imu_bno055_base:
+          Value: true
+        helena/odom:
+          Value: true
+        helena/pan_frame:
+          Value: true
+        helena/realsense_support_pan_tilt:
+          Value: true
+        helena/rear_left_axle:
+          Value: true
+        helena/rear_left_hub:
+          Value: true
+        helena/rear_left_wheel:
+          Value: true
+        helena/rear_right_axle:
+          Value: true
+        helena/rear_right_hub:
+          Value: true
+        helena/rear_right_wheel:
+          Value: true
+        helena/rear_sonar:
+          Value: true
+        helena/tilt_frame:
+          Value: true
+        helena/top_plate:
+          Value: true
+        helena/velodyne:
+          Value: true
+        helena/velodyne_base:
+          Value: true
+        map:
+          Value: true
+        world:
+          Value: true
+      Marker Scale: 0.100000001
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: true
+      Tree:
+        map:
+          helena/odom:
+            helena/base_footprint:
+              helena/base_link:
+                helena/front_left_axle:
+                  helena/front_left_hub:
+                    helena/front_left_wheel:
+                      {}
+                helena/front_right_axle:
+                  helena/front_right_hub:
+                    helena/front_right_wheel:
+                      {}
+                helena/front_sonar:
+                  {}
+                helena/rear_left_axle:
+                  helena/rear_left_hub:
+                    helena/rear_left_wheel:
+                      {}
+                helena/rear_right_axle:
+                  helena/rear_right_hub:
+                    helena/rear_right_wheel:
+                      {}
+                helena/rear_sonar:
+                  {}
+                helena/top_plate:
+                  helena/helena_box:
+                    helena/pan_frame:
+                      helena/tilt_frame:
+                        helena/realsense_support_pan_tilt:
+                          helena/camera_pan_tilt_bottom_screw_frame:
+                            helena/camera_pan_tilt_link:
+                              helena/camera_pan_tilt_color_frame:
+                                helena/camera_pan_tilt_color_optical_frame:
+                                  {}
+                              helena/camera_pan_tilt_depth_frame:
+                                helena/camera_pan_tilt_depth_optical_frame:
+                                  {}
+                              helena/camera_pan_tilt_infra1_frame:
+                                helena/camera_pan_tilt_infra1_optical_frame:
+                                  {}
+                              helena/camera_pan_tilt_infra2_frame:
+                                helena/camera_pan_tilt_infra2_optical_frame:
+                                  {}
+                  helena/helena_realsense_support:
+                    helena/camera_bottom_screw_frame:
+                      helena/camera_link:
+                        helena/camera_color_frame:
+                          helena/camera_color_optical_frame:
+                            {}
+                        helena/camera_depth_frame:
+                          helena/camera_depth_optical_frame:
+                            {}
+                        helena/camera_infra1_frame:
+                          helena/camera_infra1_optical_frame:
+                            {}
+                        helena/camera_infra2_frame:
+                          helena/camera_infra2_optical_frame:
+                            {}
+                  helena/velodyne_base:
+                    helena/velodyne:
+                      {}
+              helena/imu_bno055_base:
+                helena/imu_bno055:
+                  {}
+          world:
+            {}
+      Update Interval: 0
+      Value: true
+    - Class: rviz/Group
+      Displays:
+        - Alpha: 0.75
+          Class: rviz_plugin_tutorials/Imu
+          Color: 204; 51; 204
+          Enabled: false
+          History Length: 1
+          Name: Imu
+          Topic: /helena/sensors/imu
+          Unreliable: false
+          Value: false
+        - Class: rviz/Image
+          Enabled: true
+          Image Topic: /helena/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: 0.5
+          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: /helena/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: 16.4100227
+            Min Value: -0.00643271208
+            Value: true
+          Axis: Z
+          Channel Name: intensity
+          Class: rviz/PointCloud2
+          Color: 255; 255; 255
+          Color Transformer: AxisColor
+          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: /helena/sensors/velodyne_points
+          Unreliable: false
+          Use Fixed Frame: true
+          Use rainbow: true
+          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/LaserScan
+          Color: 255; 0; 0
+          Color Transformer: FlatColor
+          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: LaserScan
+          Position Transformer: XYZ
+          Queue Size: 10
+          Selectable: true
+          Size (Pixels): 3
+          Size (m): 0.00999999978
+          Style: Points
+          Topic: /helena/sensors/scan
+          Unreliable: false
+          Use Fixed Frame: true
+          Use rainbow: true
+          Value: true
+      Enabled: false
+      Name: Sensors
+    - Class: rviz/Group
+      Displays:
+        - Alpha: 0.699999988
+          Class: rviz/Map
+          Color Scheme: map
+          Draw Behind: true
+          Enabled: true
+          Name: Map
+          Topic: /helena/map
+          Unreliable: false
+          Use Timestamp: false
+          Value: true
+        - Angle Tolerance: 0.5
+          Class: rviz/Odometry
+          Covariance:
+            Orientation:
+              Alpha: 0.5
+              Color: 255; 255; 127
+              Color Style: Unique
+              Frame: Local
+              Offset: 1
+              Scale: 1
+              Value: true
+            Position:
+              Alpha: 0.300000012
+              Color: 204; 51; 204
+              Scale: 1
+              Value: true
+            Value: false
+          Enabled: true
+          Keep: 1000
+          Name: Odom
+          Position Tolerance: 1
+          Shape:
+            Alpha: 0.75
+            Axes Length: 1
+            Axes Radius: 0.100000001
+            Color: 255; 25; 0
+            Head Length: 0.300000012
+            Head Radius: 0.100000001
+            Shaft Length: 1
+            Shaft Radius: 0.0500000007
+            Value: Arrow
+          Topic: /helena/odom
+          Unreliable: false
+          Value: true
+        - Alpha: 1
+          Class: rviz/Polygon
+          Color: 25; 255; 0
+          Enabled: true
+          Name: footprint
+          Topic: /helena/move_base/global_costmap/footprint
+          Unreliable: false
+          Value: true
+        - Alpha: 0.5
+          Class: rviz/Map
+          Color Scheme: costmap
+          Draw Behind: true
+          Enabled: true
+          Name: local_costmap
+          Topic: /helena/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: false
+          Name: global_costmap
+          Topic: /helena/move_base/global_costmap/costmap
+          Unreliable: false
+          Use Timestamp: false
+          Value: false
+        - Alpha: 1
+          Buffer Length: 1
+          Class: rviz/Path
+          Color: 85; 255; 0
+          Enabled: true
+          Head Diameter: 0.300000012
+          Head Length: 0.200000003
+          Length: 0.300000012
+          Line Style: Lines
+          Line Width: 0.0299999993
+          Name: GlobalPlanner_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: /helena/move_base/GlobalPlanner/plan
+          Unreliable: 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: DWA_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: /helena/move_base/DWAPlannerROS/global_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: DWA_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: /helena/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: /helena/move_base/current_goal
+          Unreliable: false
+          Value: true
+      Enabled: true
+      Name: Nav
+    - Class: rviz/Group
+      Displays:
+        - Class: rviz/Group
+          Displays:
+            - Alpha: 1
+              Autocompute Intensity Bounds: true
+              Autocompute Value Bounds:
+                Max Value: 1.41061962e-08
+                Min Value: -1.07652482e-08
+                Value: true
+              Axis: Z
+              Channel Name: intensity
+              Class: rviz/LaserScan
+              Color: 255; 0; 0
+              Color Transformer: FlatColor
+              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: lidar_obstacle
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 10
+              Size (m): 0.00999999978
+              Style: Points
+              Topic: /helena/lidar_detector/scan_out
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: true
+            - Alpha: 1
+              Autocompute Intensity Bounds: true
+              Autocompute Value Bounds:
+                Max Value: 0.997381926
+                Min Value: -0.279256642
+                Value: true
+              Axis: Z
+              Channel Name: intensity
+              Class: rviz/PointCloud2
+              Color: 255; 255; 255
+              Color Transformer: Intensity
+              Decay Time: 0
+              Enabled: false
+              Invert Rainbow: false
+              Max Color: 255; 255; 255
+              Max Intensity: 0
+              Min Color: 0; 0; 0
+              Min Intensity: 0
+              Name: lidar_zone
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 2
+              Size (m): 0.00999999978
+              Style: Points
+              Topic: /helena/lidar_filter/cloud_out
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: false
+            - Class: rviz/Image
+              Enabled: false
+              Image Topic: /helena/lidar_detector/obstacles_img/image_raw
+              Max Value: 1
+              Median window: 5
+              Min Value: 0
+              Name: lidar_image
+              Normalize Range: true
+              Queue Size: 2
+              Transport Hint: raw
+              Unreliable: false
+              Value: false
+          Enabled: true
+          Name: lidar
+        - Class: rviz/Group
+          Displays:
+            - 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: near_hole_vision
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 3
+              Size (m): 0.00999999978
+              Style: Flat Squares
+              Topic: /helena/near_hole_detection/hole_zone
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              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: far_hole_vision
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 3
+              Size (m): 0.00999999978
+              Style: Flat Squares
+              Topic: /helena/far_hole_detection/hole_zone
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              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: false
+              Invert Rainbow: false
+              Max Color: 255; 255; 255
+              Max Intensity: 4096
+              Min Color: 0; 0; 0
+              Min Intensity: 0
+              Name: obstacle_vision
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 3
+              Size (m): 0.00999999978
+              Style: Squares
+              Topic: /helena/obstacle_detection_normals/all_rg
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: false
+            - Alpha: 1
+              Autocompute Intensity Bounds: true
+              Autocompute Value Bounds:
+                Max Value: 10
+                Min Value: -10
+                Value: true
+              Axis: Z
+              Channel Name: intensity
+              Class: rviz/PointCloud
+              Color: 255; 255; 255
+              Color Transformer: RGB8
+              Decay Time: 0
+              Enabled: false
+              Invert Rainbow: false
+              Max Color: 255; 255; 255
+              Max Intensity: 4096
+              Min Color: 0; 0; 0
+              Min Intensity: 0
+              Name: obstacle_normals
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 10
+              Size (m): 0.00999999978
+              Style: Points
+              Topic: /helena/obstacle_detection_normals/obstacles
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: false
+            - 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: Intensity
+              Decay Time: 0
+              Enabled: false
+              Invert Rainbow: false
+              Max Color: 255; 255; 255
+              Max Intensity: 4096
+              Min Color: 0; 0; 0
+              Min Intensity: 0
+              Name: far_hole_obstacle
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 3
+              Size (m): 0.00999999978
+              Style: Flat Squares
+              Topic: /helena/far_hole_detection/hole_obstacle
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: false
+            - 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: Intensity
+              Decay Time: 0
+              Enabled: false
+              Invert Rainbow: false
+              Max Color: 255; 255; 255
+              Max Intensity: 4096
+              Min Color: 0; 0; 0
+              Min Intensity: 0
+              Name: near_hole_obstacle
+              Position Transformer: XYZ
+              Queue Size: 10
+              Selectable: true
+              Size (Pixels): 3
+              Size (m): 0.00999999978
+              Style: Flat Squares
+              Topic: /helena/near_hole_detection/hole_obstacle
+              Unreliable: false
+              Use Fixed Frame: true
+              Use rainbow: true
+              Value: false
+          Enabled: true
+          Name: camera
+      Enabled: true
+      Name: 3d_nav_detection
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Default Light: true
+    Fixed Frame: map
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz/Interact
+      Hide Inactive Objects: true
+    - Class: rviz/MoveCamera
+    - Class: rviz/Select
+    - Class: rviz/FocusCamera
+    - Class: rviz/Measure
+    - Class: rviz/SetInitialPose
+      Topic: /helena/initialpose
+    - Class: rviz/SetGoal
+      Topic: /helena/move_base_simple/goal
+    - Class: rviz/PublishPoint
+      Single click: true
+      Topic: /clicked_point
+  Value: true
+  Views:
+    Current:
+      Class: rviz/XYOrbit
+      Distance: 36.5628128
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.0599999987
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Focal Point:
+        X: 0.248147249
+        Y: -1.80030918
+        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: 0.870397925
+      Target Frame: helena/base_footprint
+      Value: XYOrbit (rviz)
+      Yaw: 4.69358253
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: false
+  Height: 906
+  Hide Left Dock: false
+  Hide Right Dock: true
+  QMainWindow State: 000000ff00000000fd0000000400000000000001d300000344fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000344000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000001e007200650061006c00730065006e00730065005f0063006f006c006f007200000002630000011b0000001600fffffffb0000000c00540065006c0065006f00700000000315000000b30000004900fffffffb0000001e007200650061006c00730065006e00730065005f0063006f006c006f007200000002f9000001090000000000000000000000010000010f000003dafc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000003da000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006a80000007efc0100000003fb00000016006c0069006400610072005f0069006d0061006700650000000000000006a80000008200fffffffb0000000800540069006d006500000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004cf0000034400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Teleop:
+    collapsed: false
+  Time:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: true
+  Width: 1704
+  X: 111
+  Y: 78
+  lidar_image:
+    collapsed: false
+  realsense_color:
+    collapsed: false