diff --git a/rslidar_sync/README.md b/rslidar_sync/README.md
index 67d21ff..8b63cc3 100644
--- a/rslidar_sync/README.md
+++ b/rslidar_sync/README.md
@@ -17,7 +17,7 @@ roslaunch rslidar_sync rslidar_sync_3lidar.launch
+ Check the time synchronization result.
```
-rostopic echo /sync_packets_diff
+rostopic echo /sync_packet_diff
```
It shows like this, n < 4 says good time synchronization. n >= 4 says bad result.
```
diff --git a/rslidar_sync/launch/rslidar_sync_2lidar.launch b/rslidar_sync/launch/rslidar_sync_2lidar.launch
index 0660392..b0dea5a 100644
--- a/rslidar_sync/launch/rslidar_sync_2lidar.launch
+++ b/rslidar_sync/launch/rslidar_sync_2lidar.launch
@@ -9,6 +9,6 @@
-
+
diff --git a/rslidar_sync/launch/rslidar_sync_3lidar.launch b/rslidar_sync/launch/rslidar_sync_3lidar.launch
index d384798..6bbee71 100644
--- a/rslidar_sync/launch/rslidar_sync_3lidar.launch
+++ b/rslidar_sync/launch/rslidar_sync_3lidar.launch
@@ -12,6 +12,6 @@
-
+
diff --git a/rslidar_sync/src/timesync_2lidar.cpp b/rslidar_sync/src/timesync_2lidar.cpp
index aba9acc..c87285b 100644
--- a/rslidar_sync/src/timesync_2lidar.cpp
+++ b/rslidar_sync/src/timesync_2lidar.cpp
@@ -110,18 +110,18 @@ int main(int argc, char** argv)
g_skippackets_num_pub1 = nh.advertise(skippackets1_topic, 1, true);
g_skippackets_num_pub2 = nh.advertise(skippackets2_topic, true);
- std::string sync_packets_diff_topic("/sync_packets_diff");
- if (!nh_private.getParam(std::string("sync_packets_diff_topic"), sync_packets_diff_topic))
+ std::string sync_packet_diff_topic("/sync_packet_diff");
+ if (!nh_private.getParam(std::string("sync_packet_diff_topic"), sync_packet_diff_topic))
{
- ROS_ERROR("Can't get sync_packets_diff_topic, use the default sync_packets_diff_topic: %s",
- sync_packets_diff_topic.c_str());
+ ROS_ERROR("Can't get sync_packet_diff_topic, use the default sync_packet_diff_topic: %s",
+ sync_packet_diff_topic.c_str());
}
else
{
- ROS_INFO("sync_packets_diff: %s", sync_packets_diff_topic.c_str());
+ ROS_INFO("sync_packet_diff: %s", sync_packet_diff_topic.c_str());
}
- g_maxnum_diff_packetnum_pub = nh.advertise(sync_packets_diff_topic, 1, true);
+ g_maxnum_diff_packetnum_pub = nh.advertise(sync_packet_diff_topic, 1, true);
ros::spin();
return 0;
diff --git a/rslidar_sync/src/timesync_3lidar.cpp b/rslidar_sync/src/timesync_3lidar.cpp
index 5ed43d6..30bcc42 100644
--- a/rslidar_sync/src/timesync_3lidar.cpp
+++ b/rslidar_sync/src/timesync_3lidar.cpp
@@ -209,17 +209,17 @@ int main(int argc, char** argv)
g_skippackets_num_pub2 = nh.advertise(skippackets2_topic.c_str(), 1, true);
g_skippackets_num_pub3 = nh.advertise(skippackets3_topic.c_str(), 1, true);
- std::string sync_packets_diff_topic("/sync_packets_diff");
- if (!nh_private.getParam(std::string("sync_packets_diff_topic"), sync_packets_diff_topic))
+ std::string sync_packet_diff_topic("/sync_packet_diff");
+ if (!nh_private.getParam(std::string("sync_packet_diff_topic"), sync_packet_diff_topic))
{
- ROS_ERROR("Can't get sync_packets_diff_topic, use the default sync_packets_diff_topic: %s",
- sync_packets_diff_topic.c_str());
+ ROS_ERROR("Can't get sync_packet_diff_topic, use the default sync_packet_diff_topic: %s",
+ sync_packet_diff_topic.c_str());
}
else
{
- ROS_INFO("sync_packets_diff: %s", sync_packets_diff_topic.c_str());
+ ROS_INFO("sync_packet_diff: %s", sync_packet_diff_topic.c_str());
}
- g_maxnum_diff_packetnum_pub = nh.advertise(sync_packets_diff_topic, 1, true);
+ g_maxnum_diff_packetnum_pub = nh.advertise(sync_packet_diff_topic, 1, true);
ros::spin();
return 0;