diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp
index 51d24004f1627b3a2c77799d1f6730a832c3861a..4ec60097a28d2dd683f31b4309c1d12687c83a87 100644
--- a/src/subscriber_gnss_fix.cpp
+++ b/src/subscriber_gnss_fix.cpp
@@ -46,7 +46,7 @@ SubscriberGnssFix::SubscriberGnssFix(const std::string& _unique_name,
 
 void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_     = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this);
+    sub_     = nh.subscribe(topic, 1e3, &SubscriberGnssFix::callback, this);
 }
 
 void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg)
diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp
index 612368526a59a2ec32a470892ae9710213b7e335..2a9d3dcbf1f1d70f62950b8dc3f4241a48e4b49c 100644
--- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp
+++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp
@@ -39,7 +39,7 @@ void SubscriberGnssFixNovatelPublisherEcef::initialize(ros::NodeHandle& nh, cons
 {
     SubscriberGnssFixPublisherEcef::initialize(nh, topic);
     sub_.shutdown();
-    sub_    = nh.subscribe(topic, 1, &SubscriberGnssFixNovatelPublisherEcef::callback, this);
+    sub_    = nh.subscribe(topic, 1e3, &SubscriberGnssFixNovatelPublisherEcef::callback, this);
 }
 
 void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& _msg)
diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp
index 8faf1ece26045ea3e6c9c6883d6fff4fdcfd6c93..44db5def798bd6a4c9c39952973e9b6bd92bcfe3 100644
--- a/src/subscriber_gnss_fix_publisher_ecef.cpp
+++ b/src/subscriber_gnss_fix_publisher_ecef.cpp
@@ -55,7 +55,7 @@ SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string
 
 void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic)
 {
-    sub_    = nh.subscribe(topic, 1, &SubscriberGnssFixPublisherEcef::callback, this);
+    sub_    = nh.subscribe(topic, 1e3, &SubscriberGnssFixPublisherEcef::callback, this);
 
     // initialize msgs and publishers
     pose_msg_.header.frame_id = "ENU";