diff --git a/launch/bringup.launch b/launch/bringup.launch
index eebdf7033890fd18b594b4d9973144568f01934d..57cc9de71762f5c68739f44f7507d00b0ac5121b 100644
--- a/launch/bringup.launch
+++ b/launch/bringup.launch
@@ -3,25 +3,26 @@
   
   <arg name="ns" default="helena"/>
   
-  <!--enable/disable-->
-  <arg name="front_laser"     default="true"/>
-  <arg name="rear_laser"      default="true"/>
-  <arg name="joy"             default="true"/>
-  <arg name="platform"        default="true"/>
-  
-  <arg name="pioneer_config_file"     default="$(find iri_helena_bringup)/config/pioneer_params.yaml" />
-  <arg name="front_laser_config_file" default="$(find iri_helena_bringup)/config/hokuyo_utm30lx_usb.yaml" />
-  <arg name="rear_laser_config_file"  default="$(find iri_helena_bringup)/config/hokuyo_utm30lx_eth.yaml" />
-  <arg name="joy_config_file"         default="$(find iri_helena_bringup)/config/joy_params.yaml" />
+  <arg name="pioneer_config_file"     default="$(find iri_helena_bringup)/config/helena_pioneer.yaml" />
+
+  <arg name="robosense_config_file" default="$(find iri_helena_bringup)/config/helena_rs16.yaml" />
+  <arg name="robosense_node_name"   default="front_laser" />
+
+  <arg name="realsense_config_file" default="$(find iri_helena_bringup)/config/helena_realsense.yaml" />
+  <arg name="realsense_camera_name" default="nav_cam"/>
+  <arg name="realsense_tf_prefix"   default="$(arg ns)"/>
+
+  <arg name="imu_config_file"      default="$(find iri_helena_bringup)/config/helena_bno055.yaml" />
+  <arg name="imu_calibration_file" default="$(find iri_helena_bringup)/calibration/bno055.cal" />
+  <arg name="imu_node_name"        default="bno055_imu"/>
 
-  <arg name="output" default="log"/>
+  <arg name="output" default="screen"/>
   <arg name="launch_prefix" default=""/>
 
   <remap from="/$(arg ns)/rosaria/cmd_vel" to="/$(arg ns)/cmd_vel"/>
   <remap from="/$(arg ns)/rosaria/pose"    to="/$(arg ns)/odom"/>
 
-  <include file="$(find iri_pioneer3_bringup)/launch/bringup.launch"
-            if="$(arg platform)" >
+  <include file="$(find iri_pioneer3_bringup)/launch/bringup.launch">
     <arg name="ns"            value="$(arg ns)"/>
     <arg name="config_file"   value="$(arg pioneer_config_file)"/>
     <arg name="output"        value="$(arg output)"/>
@@ -32,51 +33,29 @@
 
     <group ns="sensors">
       
-     <include file="$(find iri_hokuyo_laser2d_bringup)/launch/hokuyo_laser2d.launch"
-              if="$(arg front_laser)" >
-        <arg name="config_file"   value="$(arg front_laser_config_file)"/>
-        <arg name="node_name"     value="front_laser"/>
-        <arg name="scan_topic"    value="/$(arg ns)/sensors/front_laser_scan"/>
-        <arg name="status_topic"  value="/$(arg ns)/sensors/front_laser_status"/>
+      <include file="$(find iri_robosense_lidar_bringup)/launch/robosense_rs16.launch">
+        <arg name="config_file"   value="$(arg robosense_config_file)"/>
+        <arg name="node_name"     value="$(arg robosense_node_name)"/>
         <arg name="output"        value="$(arg output)"/>
         <arg name="launch_prefix" value="$(arg launch_prefix)"/>
       </include>
 
-      <include file="$(find iri_hokuyo_laser2d_bringup)/launch/hokuyo_laser2d.launch"
-               if="$(arg rear_laser)" >
-        <arg name="config_file"   value="$(arg rear_laser_config_file)"/>
-        <arg name="node_name"     value="rear_laser"/>
-        <arg name="scan_topic"    value="/$(arg ns)/sensors/rear_laser_scan"/>
-        <arg name="status_topic"  value="/$(arg ns)/sensors/rear_laser_status"/>
-        <arg name="output"        value="$(arg output)"/>
-        <arg name="launch_prefix" value="$(arg launch_prefix)"/>
+<!--      <include file="$(find iri_realsense_depth_bringup)/launch/realsense.launch">
+        <arg name="config_file" value="$(arg realsense_config_file)"/>
+        <arg name="camera_name" value="$(arg realsense_camera_name)"/>
+        <arg name="tf_prefix"   value="$(arg realsense_tf_prefix)"/>
+      </include>-->
+
+      <include file="$(find iri_bno055_imu_bringup)/launch/bno055_imu.launch">
+        <arg name="config_file"      value="$(arg imu_config_file)"/>
+        <arg name="calibration_file" value="$(arg imu_calibration_file)"/>
+        <arg name="node_name"        value="$(arg imu_node_name)"/>
+        <arg name="output"           value="$(arg output)"/>
+        <arg name="launch_prefix"    value="$(arg launch_prefix)"/>
       </include>
 
-      <node pkg="joy"
-            type="joy_node"
-            name="joy_node"
-            if="$(arg joy)"
-            respawn="true"> 
-        <rosparam file="$(arg joy_config_file)" command="load" />
-        <remap from="~joy" to="/$(arg ns)/sensors/joy"/>
-      </node>
-      
-      <!--TODO gps -->
-      
-      <!--TODO camera -->
-      
-      <!--TODO battery_monitor -->
-
-    </group>
-
-    <group ns="devices">
-
-      <!--TODO pan & tilt -->
-
-      <!--TODO tts -->
-
     </group>
 
   </group>
 
-</launch>
\ No newline at end of file
+</launch>
diff --git a/launch/test.launch b/launch/test.launch
index 8e76ca69a6e696eaa8832b6c2a44f2bfbe5c9e72..9c44a6d34209e3ca69d1e9181a2939bccb14e4c1 100644
--- a/launch/test.launch
+++ b/launch/test.launch
@@ -3,7 +3,7 @@
 
   <arg name="ns"                 default="helena" />
   <arg name="model"              default="$(arg ns)"/>
-  <arg name="output"             default="log" />
+  <arg name="output"             default="screen" />
   <arg name="launch_prefix"      default="" />
 
   <include file="$(find iri_helena_bringup)/launch/bringup.launch">
@@ -24,4 +24,4 @@
         args="-d $(find iri_helena_bringup)/rviz/$(arg ns).rviz">
   </node>
 
-</launch>
\ No newline at end of file
+</launch>
diff --git a/rviz/helena.rviz b/rviz/helena.rviz
index c2d6b3681b924f0133983119e31e4b21de8e00d2..be20ed1838cf3d49c464937f739711a484bb10e0 100644
--- a/rviz/helena.rviz
+++ b/rviz/helena.rviz
@@ -26,7 +26,7 @@ Panels:
     Experimental: false
     Name: Time
     SyncMode: 0
-    SyncSource: FrontLaserScan
+    SyncSource: robosense
 Toolbars:
   toolButtonStyle: 2
 Visualization Manager:
@@ -59,10 +59,6 @@ Visualization Manager:
           Value: true
         helena/base_link:
           Value: true
-        helena/front_hokuyo_base:
-          Value: true
-        helena/front_hokuyo_scan_frame:
-          Value: true
         helena/front_left_axle:
           Value: true
         helena/front_left_hub:
@@ -77,11 +73,13 @@ Visualization Manager:
           Value: true
         helena/front_sonar:
           Value: true
-        helena/odom:
+        helena/helena_box:
           Value: true
-        helena/rear_hokuyo_base:
+        helena/imu_bno055:
           Value: true
-        helena/rear_hokuyo_scan_frame:
+        helena/imu_bno055_base:
+          Value: true
+        helena/odom:
           Value: true
         helena/rear_left_axle:
           Value: true
@@ -97,11 +95,11 @@ Visualization Manager:
           Value: true
         helena/rear_sonar:
           Value: true
-        helena/sensors_base:
+        helena/robosense:
           Value: true
-        helena/top_plate:
+        helena/robosense_base:
           Value: true
-        map:
+        helena/top_plate:
           Value: true
       Marker Scale: 0.25
       Name: TF
@@ -122,6 +120,8 @@ Visualization Manager:
                     {}
               helena/front_sonar:
                 {}
+              helena/helena_box:
+                {}
               helena/rear_left_axle:
                 helena/rear_left_hub:
                   helena/rear_left_wheel:
@@ -132,17 +132,14 @@ Visualization Manager:
                     {}
               helena/rear_sonar:
                 {}
-              helena/sensors_base:
-                helena/front_hokuyo_base:
-                  helena/front_hokuyo_scan_frame:
-                    {}
-                helena/rear_hokuyo_base:
-                  helena/rear_hokuyo_scan_frame:
-                    {}
+              helena/robosense_base:
+                helena/robosense:
+                  {}
               helena/top_plate:
                 {}
-        map:
-          {}
+            helena/imu_bno055_base:
+              helena/imu_bno055:
+                {}
       Update Interval: 0
       Value: true
     - Alpha: 0.899999976
@@ -164,15 +161,6 @@ Visualization Manager:
           Show Axes: false
           Show Trail: false
           Value: true
-        front_hokuyo_base:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
-          Value: true
-        front_hokuyo_scan_frame:
-          Alpha: 1
-          Show Axes: false
-          Show Trail: false
         front_left_axle:
           Alpha: 1
           Show Axes: false
@@ -208,12 +196,17 @@ Visualization Manager:
           Show Axes: false
           Show Trail: false
           Value: true
-        rear_hokuyo_base:
+        helena_box:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
+          Value: true
+        imu_bno055:
           Alpha: 1
           Show Axes: false
           Show Trail: false
           Value: true
-        rear_hokuyo_scan_frame:
+        imu_bno055_base:
           Alpha: 1
           Show Axes: false
           Show Trail: false
@@ -252,11 +245,15 @@ Visualization Manager:
           Show Axes: false
           Show Trail: false
           Value: true
-        sensors_base:
+        robosense:
           Alpha: 1
           Show Axes: false
           Show Trail: false
           Value: true
+        robosense_base:
+          Alpha: 1
+          Show Axes: false
+          Show Trail: false
         top_plate:
           Alpha: 1
           Show Axes: false
@@ -307,33 +304,33 @@ Visualization Manager:
         - Alpha: 1
           Autocompute Intensity Bounds: true
           Autocompute Value Bounds:
-            Max Value: 10
-            Min Value: -10
+            Max Value: 1.86796319
+            Min Value: -5.28491831
             Value: true
-          Axis: Z
-          Channel Name: intensity
-          Class: rviz/LaserScan
-          Color: 255; 0; 0
-          Color Transformer: FlatColor
+          Axis: X
+          Channel Name: x
+          Class: rviz/PointCloud2
+          Color: 255; 255; 255
+          Color Transformer: Intensity
           Decay Time: 0
-          Enabled: true
+          Enabled: false
           Invert Rainbow: false
           Max Color: 255; 255; 255
-          Max Intensity: 999999
+          Max Intensity: 1.85023665
           Min Color: 0; 0; 0
-          Min Intensity: 1.50313361e-19
-          Name: FrontLaserScan
+          Min Intensity: -5.28405237
+          Name: SonarPointCloud2
           Position Transformer: XYZ
           Queue Size: 10
           Selectable: true
-          Size (Pixels): 3
+          Size (Pixels): 20
           Size (m): 0.00999999978
           Style: Points
-          Topic: /helena/sensors/front_laser_scan
+          Topic: /helena/rosaria/sonar_pointcloud2
           Unreliable: false
           Use Fixed Frame: true
           Use rainbow: true
-          Value: true
+          Value: false
         - Alpha: 1
           Autocompute Intensity Bounds: true
           Autocompute Value Bounds:
@@ -342,58 +339,28 @@ Visualization Manager:
             Value: true
           Axis: Z
           Channel Name: intensity
-          Class: rviz/LaserScan
-          Color: 255; 170; 0
-          Color Transformer: FlatColor
-          Decay Time: 0
-          Enabled: true
-          Invert Rainbow: false
-          Max Color: 255; 255; 255
-          Max Intensity: 999999
-          Min Color: 0; 0; 0
-          Min Intensity: 1.50313361e-19
-          Name: RearLaserScan
-          Position Transformer: XYZ
-          Queue Size: 10
-          Selectable: true
-          Size (Pixels): 3
-          Size (m): 0.00999999978
-          Style: Points
-          Topic: /helena/sensors/rear_laser_scan
-          Unreliable: false
-          Use Fixed Frame: true
-          Use rainbow: true
-          Value: true
-        - Alpha: 1
-          Autocompute Intensity Bounds: true
-          Autocompute Value Bounds:
-            Max Value: 1.86796319
-            Min Value: -5.28491831
-            Value: true
-          Axis: X
-          Channel Name: x
           Class: rviz/PointCloud2
           Color: 255; 255; 255
           Color Transformer: Intensity
           Decay Time: 0
-          Enabled: false
+          Enabled: true
           Invert Rainbow: false
           Max Color: 255; 255; 255
-          Max Intensity: 1.85023665
+          Max Intensity: 255
           Min Color: 0; 0; 0
-          Min Intensity: -5.28405237
-          Name: SonarPointCloud2
+          Min Intensity: 0.462781101
+          Name: robosense
           Position Transformer: XYZ
           Queue Size: 10
           Selectable: true
-          Size (Pixels): 20
+          Size (Pixels): 3
           Size (m): 0.00999999978
-          Style: Points
-          Topic: /helena/rosaria/sonar_pointcloud2
+          Style: Flat Squares
+          Topic: /helena/sensors/rslidar_points
           Unreliable: false
           Use Fixed Frame: true
           Use rainbow: true
-          Value: false
+          Value: true
       Enabled: true
       Name: Sensors
   Enabled: true