diff --git a/CMakeLists.txt b/CMakeLists.txt
index 54432737be56e169a19c1c0f5a7d5c2684fddf91..a459fa15dc1983a336dc48c78e939a921de07574 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -178,8 +178,7 @@ target_link_libraries(wolf_subscriber_gnss_TDCP
 					  ${wolf_LIBRARIES} 
 					  ${wolfgnss_LIBRARIES} 
 					  ${iri_gnss_msgs_LIBRARIES}
-            )
-            
+            		  )
 target_link_libraries(wolf_subscriber_gnss_ublox 
 					  ${wolf_LIBRARIES} 
 					  ${wolfgnss_LIBRARIES} 
diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp
index 58d304b147d19a6d9b9f3e3c45d88f60b0e7ad3d..33bcbff9b2a85f4f96627ac52df6356a619b0e58 100644
--- a/src/wolf_subscriber_gnss_ublox.cpp
+++ b/src/wolf_subscriber_gnss_ublox.cpp
@@ -11,7 +11,7 @@ WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr
 
 void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_     = nh.subscribe(topic, 10, &WolfSubscriberGnssUblox::callback, this);
+    sub_     = nh.subscribe(topic, 100, &WolfSubscriberGnssUblox::callback, this);
 }
 
 void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg)