diff --git a/src/automatic_start.cpp b/src/automatic_start.cpp index da52dcc..f39b9d4 100644 --- a/src/automatic_start.cpp +++ b/src/automatic_start.cpp @@ -815,7 +815,7 @@ bool AutomaticStart::topicCheck(void) { for (int i = 0; i < int(topic_check_topics_.size()); i++) { - if (topic_check_topics_[i].getTime() != ros::Time::UNINITIALIZED && + if (topic_check_topics_[i].getTime() == ros::Time::UNINITIALIZED || (ros::Time::now() - topic_check_topics_[i].getTime()) > ros::Duration(_topic_check_timeout_)) { missing_topics << std::endl << "\t" << topic_check_topics_[i].getTopicName(); diff --git a/test/topic_check/test.cpp b/test/topic_check/test.cpp index 10dc8e8..f0cda40 100644 --- a/test/topic_check/test.cpp +++ b/test/topic_check/test.cpp @@ -15,7 +15,7 @@ bool Tester::test() { if (!success) { return true; } else { - ROS_ERROR("[%s]: takeoff initiated, this should not be possible", ros::this_node::getName().c_str()); + ROS_ERROR("[%s]: takeoff initiated, this should not be possible: '%s'", ros::this_node::getName().c_str(), message.c_str()); return false; } }