test_log_utils.cpp
Go to the documentation of this file.
2 #include <ros/ros.h>
3 #include <std_msgs/Header.h>
4 #include <gtest/gtest.h>
5 
6 
7 TEST(LogUtils, testWarnNoRemap){
9  ros::Publisher pub_remap = pnh.advertise<std_msgs::Header>(
10  /*topic=*/"remap", /*queue_size=*/10);
11  ros::Publisher pub_noremap = pnh.advertise<std_msgs::Header>(
12  /*topic=*/"noremap", /*queue_size=*/10);
13 
14  std::vector<std::string> topics;
15  topics.push_back(std::string("~remap"));
16  bool actual;
17  actual = jsk_topic_tools::warnNoRemap(topics);
18  EXPECT_EQ(true, actual);
19 
20  topics.push_back(std::string("~noremap"));
21  actual = jsk_topic_tools::warnNoRemap(topics);
22  EXPECT_EQ(false, actual);
23 }
24 
25 TEST(LogUtils, testGetFunctionName){
26  std::string name = std::string(
27  "virtual void jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent&)");
28  std::string actual = jsk_topic_tools::getFunctionName(name);
29  std::string expected = std::string("jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback");
30  ASSERT_STREQ(expected.c_str(), actual.c_str());
31 }
32 
33 TEST(LogUtils, testJSKROSXXX){
34  JSK_ROS_DEBUG("Testing JSK_ROS_DEBUG: %ld", ros::Time::now().toNSec());
35  JSK_ROS_INFO("Testing JSK_ROS_INFO: %ld", ros::Time::now().toNSec());
36  JSK_ROS_WARN("Testing JSK_ROS_WARN: %ld", ros::Time::now().toNSec());
37  JSK_ROS_ERROR("Testing JSK_ROS_ERROR: %ld", ros::Time::now().toNSec());
38  JSK_ROS_FATAL("Testing JSK_ROS_FATAL: %ld", ros::Time::now().toNSec());
39 
40  JSK_ROS_DEBUG_STREAM("Testing " << "JSK_ROS_DEBUG_STREAM: " << ros::Time::now().toNSec());
41  JSK_ROS_INFO_STREAM("Testing " << "JSK_ROS_INFO_STREAM: " << ros::Time::now().toNSec());
42  JSK_ROS_WARN_STREAM("Testing " << "JSK_ROS_WARN_STREAM: " << ros::Time::now().toNSec());
43  JSK_ROS_ERROR_STREAM("Testing " << "JSK_ROS_ERROR_STREAM: " << ros::Time::now().toNSec());
44  JSK_ROS_FATAL_STREAM("Testing " << "JSK_ROS_FATAL_STREAM: " << ros::Time::now().toNSec());
45 
46  JSK_ROS_DEBUG_THROTTLE(1, "Testing JSK_ROS_DEBUG_THROTTLE: %ld", ros::Time::now().toNSec());
47  JSK_ROS_INFO_THROTTLE(1, "Testing JSK_ROS_INFO_THROTTLE: %ld", ros::Time::now().toNSec());
48  JSK_ROS_WARN_THROTTLE(1, "Testing JSK_ROS_WARN_THROTTLE: %ld", ros::Time::now().toNSec());
49  JSK_ROS_ERROR_THROTTLE(1, "Testing JSK_ROS_ERROR_THROTTLE: %ld", ros::Time::now().toNSec());
50  JSK_ROS_FATAL_THROTTLE(1, "Testing JSK_ROS_FATAL_THROTTLE: %ld", ros::Time::now().toNSec());
51 
52  JSK_ROS_DEBUG_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_DEBUG_STREAM_THROTTLE: " << ros::Time::now().toNSec());
53  JSK_ROS_INFO_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_INFO_STREAM_THROTTLE: " << ros::Time::now().toNSec());
54  JSK_ROS_WARN_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_WARN_STREAM_THROTTLE: " << ros::Time::now().toNSec());
55  JSK_ROS_ERROR_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_ERROR_STREAM_THROTTLE: " << ros::Time::now().toNSec());
56  JSK_ROS_FATAL_STREAM_THROTTLE(1, "Testing " << "JSK_ROS_FATAL_STREAM_THROTTLE: " << ros::Time::now().toNSec());
57 }
58 
59 int main(int argc, char **argv){
60  ros::init(argc, argv, "test_log_utils");
61  testing::InitGoogleTest(&argc, argv);
62  return RUN_ALL_TESTS();
63 }
#define JSK_ROS_WARN(str,...)
Definition: log_utils.h:141
#define JSK_ROS_DEBUG_STREAM_THROTTLE(rate,...)
Definition: log_utils.h:183
#define JSK_ROS_INFO_THROTTLE(rate, str,...)
Definition: log_utils.h:170
const std::string getFunctionName(const std::string &name)
Get only function name from PRETTY_FUNCTION
Definition: log_utils.cpp:62
#define JSK_ROS_DEBUG(str,...)
Definition: log_utils.h:135
#define JSK_ROS_FATAL_STREAM(...)
Definition: log_utils.h:163
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define JSK_ROS_WARN_STREAM(...)
Definition: log_utils.h:157
TEST(LogUtils, testWarnNoRemap)
#define JSK_ROS_INFO(str,...)
Definition: log_utils.h:138
#define JSK_ROS_FATAL(str,...)
Definition: log_utils.h:147
#define JSK_ROS_ERROR_STREAM(...)
Definition: log_utils.h:160
#define JSK_ROS_FATAL_STREAM_THROTTLE(rate,...)
Definition: log_utils.h:195
int main(int argc, char **argv)
#define JSK_ROS_DEBUG_STREAM(...)
Definition: log_utils.h:151
bool warnNoRemap(const std::vector< std::string > names)
warn if there are expected remappings.
Definition: log_utils.cpp:44
#define JSK_ROS_ERROR_STREAM_THROTTLE(rate,...)
Definition: log_utils.h:192
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define JSK_ROS_INFO_STREAM_THROTTLE(rate,...)
Definition: log_utils.h:186
#define JSK_ROS_DEBUG_THROTTLE(rate, str,...)
Definition: log_utils.h:167
#define JSK_ROS_ERROR(str,...)
Definition: log_utils.h:144
#define JSK_ROS_ERROR_THROTTLE(rate, str,...)
Definition: log_utils.h:176
#define JSK_ROS_WARN_THROTTLE(rate, str,...)
Definition: log_utils.h:173
static Time now()
#define JSK_ROS_WARN_STREAM_THROTTLE(rate,...)
Definition: log_utils.h:189
#define JSK_ROS_INFO_STREAM(...)
Definition: log_utils.h:154
#define JSK_ROS_FATAL_THROTTLE(rate, str,...)
Definition: log_utils.h:179


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:19