diff --git a/piksi_multi_rtk_ros/README.md b/piksi_multi_rtk_ros/README.md
index 3761f655..a695c3e2 100644
--- a/piksi_multi_rtk_ros/README.md
+++ b/piksi_multi_rtk_ros/README.md
@@ -5,6 +5,8 @@ ROS node to read SBP messages from an attached Piksi **Multi** RTK device.
The piksi_multi_rtk_ros package has been tested under:
* [ROS] Indigo and Ubuntu 14.04, and [ROS] Kinetic and Ubuntu 16.04;
* The latest version relies on Piksi Multi Firmware **1.2.14** release (see [Swift Nav firmware page](https://support.swiftnav.com/customer/en/portal/articles/2492784-piksi-multi-and-duro-firmware)).
+
+**WARNING:** default baud rate of the driver is set to '230400' (default baud rate of Piksi Multi is '115200'). This means you have to set your Piksi Multi baud rate correctly by following [these settings instructions](https://github.com/ethz-asl/ethz_piksi_ros/wiki/Installing-and-Configuring-Your-Piksi#settings).
## Installation and Configuration
@@ -25,7 +27,7 @@ source install/install_piksi_multi.sh
```
## Usage
-Make sure you configured your Piksi(s) by following [these instructions](https://github.com/ethz-asl/ethz_piksi_ros/wiki/Installing-and-Configuring-Your-Piksi).
+**Make sure** you configured your Piksi(s) by following [these instructions](https://github.com/ethz-asl/ethz_piksi_ros/wiki/Installing-and-Configuring-Your-Piksi).
**Base station**
diff --git a/piksi_multi_rtk_ros/cfg/piksi_multi_driver_settings.yaml b/piksi_multi_rtk_ros/cfg/piksi_multi_driver_settings.yaml
index d0e6f15b..407221f8 100644
--- a/piksi_multi_rtk_ros/cfg/piksi_multi_driver_settings.yaml
+++ b/piksi_multi_rtk_ros/cfg/piksi_multi_driver_settings.yaml
@@ -1,13 +1,13 @@
# General Settings.
serial_port: '/dev/ttyUSB0'
-baud_rate: 115200
+baud_rate: 230400
base_station_mode: false
debug_mode: false # if true, output every topic read by this driver
# whenever possible, use network broadcast, not global ip broadcast
# use ifconfig to show network broadcast (or calculate it yourself....).
-broadcast_addr: 10.10.10.255
+broadcast_addr: 192.168.0.255
broadcast_port: 26078
-base_station_ip_for_latency_estimation: 10.10.10.1 # ip base station if you want to estimate latency.
+base_station_ip_for_latency_estimation: 192.168.0.1 # ip base station if you want to estimate latency.
# Coordinate frame of the GPS receiver with respect to the base link.
navsatfix_frame_id: 'base_link'
diff --git a/piksi_multi_rtk_ros/launch/piksi_multi_base_station.launch b/piksi_multi_rtk_ros/launch/piksi_multi_base_station.launch
index ca24dbac..c564021e 100644
--- a/piksi_multi_rtk_ros/launch/piksi_multi_base_station.launch
+++ b/piksi_multi_rtk_ros/launch/piksi_multi_base_station.launch
@@ -8,7 +8,7 @@
-
+
diff --git a/piksi_multi_rtk_ros/package.xml b/piksi_multi_rtk_ros/package.xml
index 16ab0d04..28cc6411 100644
--- a/piksi_multi_rtk_ros/package.xml
+++ b/piksi_multi_rtk_ros/package.xml
@@ -1,7 +1,7 @@
piksi_multi_rtk_ros
- 1.0.0
+ 1.0.1
ROS driver for Piksi Multi RTK GPS Receiver.