Skip to content

Commit

Permalink
feat: fix sync_packets_diff_topic to origin sync_packets_diff_topic t…
Browse files Browse the repository at this point in the history
…o keep origin launch right
  • Loading branch information
zhangbaoxian committed Feb 21, 2019
1 parent b440aaa commit cec72bb
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 15 deletions.
2 changes: 1 addition & 1 deletion rslidar_sync/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
```
Expand Down
2 changes: 1 addition & 1 deletion rslidar_sync/launch/rslidar_sync_2lidar.launch
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,6 @@
<param name="skippackets1_topic" value="/left/skippackets_num"/>
<param name="skippackets2_topic" value="/middle/skippackets_num"/>

<param name="sync_packets_diff_topic" value="/sync_packets_diff"/>
<param name="sync_packet_diff_topic" value="/sync_packet_diff"/>
</node>
</launch>
2 changes: 1 addition & 1 deletion rslidar_sync/launch/rslidar_sync_3lidar.launch
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,6 @@
<param name="skippackets2_topic" value="/middle/skippackets_num"/>
<param name="skippackets3_topic" value="/right/skippackets_num"/>

<param name="sync_packets_diff_topic" value="/sync_packets_diff"/>
<param name="sync_packet_diff_topic" value="/sync_packet_diff"/>
</node>
</launch>
12 changes: 6 additions & 6 deletions rslidar_sync/src/timesync_2lidar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,18 +110,18 @@ int main(int argc, char** argv)
g_skippackets_num_pub1 = nh.advertise<std_msgs::Int32>(skippackets1_topic, 1, true);
g_skippackets_num_pub2 = nh.advertise<std_msgs::Int32>(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<std_msgs::String>(sync_packets_diff_topic, 1, true);
g_maxnum_diff_packetnum_pub = nh.advertise<std_msgs::String>(sync_packet_diff_topic, 1, true);

ros::spin();
return 0;
Expand Down
12 changes: 6 additions & 6 deletions rslidar_sync/src/timesync_3lidar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,17 +209,17 @@ int main(int argc, char** argv)
g_skippackets_num_pub2 = nh.advertise<std_msgs::Int32>(skippackets2_topic.c_str(), 1, true);
g_skippackets_num_pub3 = nh.advertise<std_msgs::Int32>(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<std_msgs::String>(sync_packets_diff_topic, 1, true);
g_maxnum_diff_packetnum_pub = nh.advertise<std_msgs::String>(sync_packet_diff_topic, 1, true);

ros::spin();
return 0;
Expand Down

0 comments on commit cec72bb

Please sign in to comment.