Go to the documentation of this file.00001 #include "jsk_topic_tools/log_utils.h"
00002 #include <ros/ros.h>
00003 #include <std_msgs/Header.h>
00004 #include <gtest/gtest.h>
00005
00006
00007 TEST(LogUtils, testWarnNoRemap){
00008 ros::NodeHandle pnh = ros::NodeHandle("~");
00009 ros::Publisher pub_remap = pnh.advertise<std_msgs::Header>(
00010 "remap", 10);
00011 ros::Publisher pub_noremap = pnh.advertise<std_msgs::Header>(
00012 "noremap", 10);
00013
00014 std::vector<std::string> topics;
00015 topics.push_back(std::string("~remap"));
00016 bool actual;
00017 actual = jsk_topic_tools::warnNoRemap(topics);
00018 EXPECT_EQ(true, actual);
00019
00020 topics.push_back(std::string("~noremap"));
00021 actual = jsk_topic_tools::warnNoRemap(topics);
00022 EXPECT_EQ(false, actual);
00023 }
00024
00025 TEST(LogUtils, testGetFunctionName){
00026 std::string name = std::string(
00027 "virtual void jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent&)");
00028 std::string actual = jsk_topic_tools::getFunctionName(name);
00029 std::string expected = std::string("jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback");
00030 ASSERT_STREQ(expected.c_str(), actual.c_str());
00031 }
00032
00033 TEST(LogUtils, testJSKROSXXX){
00034 JSK_ROS_DEBUG("Testing JSK_ROS_DEBUG: %ld", ros::Time::now().toNSec());
00035 JSK_ROS_INFO("Testing JSK_ROS_INFO: %ld", ros::Time::now().toNSec());
00036 JSK_ROS_WARN("Testing JSK_ROS_WARN: %ld", ros::Time::now().toNSec());
00037 JSK_ROS_ERROR("Testing JSK_ROS_ERROR: %ld", ros::Time::now().toNSec());
00038 JSK_ROS_FATAL("Testing JSK_ROS_FATAL: %ld", ros::Time::now().toNSec());
00039
00040 JSK_ROS_DEBUG_STREAM("Testing " << "JSK_ROS_DEBUG_STREAM: " << ros::Time::now().toNSec());
00041 JSK_ROS_INFO_STREAM("Testing " << "JSK_ROS_INFO_STREAM: " << ros::Time::now().toNSec());
00042 JSK_ROS_WARN_STREAM("Testing " << "JSK_ROS_WARN_STREAM: " << ros::Time::now().toNSec());
00043 JSK_ROS_ERROR_STREAM("Testing " << "JSK_ROS_ERROR_STREAM: " << ros::Time::now().toNSec());
00044 JSK_ROS_FATAL_STREAM("Testing " << "JSK_ROS_FATAL_STREAM: " << ros::Time::now().toNSec());
00045
00046 JSK_ROS_DEBUG_THROTTLE(1, "Testing JSK_ROS_DEBUG_THROTTLE: %ld", ros::Time::now().toNSec());
00047 JSK_ROS_INFO_THROTTLE(1, "Testing JSK_ROS_INFO_THROTTLE: %ld", ros::Time::now().toNSec());
00048 JSK_ROS_WARN_THROTTLE(1, "Testing JSK_ROS_WARN_THROTTLE: %ld", ros::Time::now().toNSec());
00049 JSK_ROS_ERROR_THROTTLE(1, "Testing JSK_ROS_ERROR_THROTTLE: %ld", ros::Time::now().toNSec());
00050 JSK_ROS_FATAL_THROTTLE(1, "Testing JSK_ROS_FATAL_THROTTLE: %ld", ros::Time::now().toNSec());
00051
00052 JSK_ROS_DEBUG_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_DEBUG_STREAM_THROTTLE: " << ros::Time::now().toNSec());
00053 JSK_ROS_INFO_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_INFO_STREAM_THROTTLE: " << ros::Time::now().toNSec());
00054 JSK_ROS_WARN_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_WARN_STREAM_THROTTLE: " << ros::Time::now().toNSec());
00055 JSK_ROS_ERROR_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_ERROR_STREAM_THROTTLE: " << ros::Time::now().toNSec());
00056 JSK_ROS_FATAL_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_FATAL_STREAM_THROTTLE: " << ros::Time::now().toNSec());
00057 }
00058
00059 int main(int argc, char **argv){
00060 ros::init(argc, argv, "test_log_utils");
00061 testing::InitGoogleTest(&argc, argv);
00062 return RUN_ALL_TESTS();
00063 }