Actually delay messages. (#406)

master
Juraj Oršulić 2017-07-05 11:17:42 +02:00 committed by Holger Rapp
parent 84b14a4774
commit 764004736e
1 changed files with 1 additions and 1 deletions

View File

@ -193,7 +193,7 @@ void Run(const std::vector<string>& bag_filenames) {
while (!delayed_messages.empty() && while (!delayed_messages.empty() &&
delayed_messages.front().getTime() < delayed_messages.front().getTime() <
msg.getTime() + ::ros::Duration(1.)) { msg.getTime() - ::ros::Duration(1.)) {
const rosbag::MessageInstance& delayed_msg = delayed_messages.front(); const rosbag::MessageInstance& delayed_msg = delayed_messages.front();
const string topic = node.node_handle()->resolveName( const string topic = node.node_handle()->resolveName(
delayed_msg.getTopic(), false /* resolve */); delayed_msg.getTopic(), false /* resolve */);