3 #include <std_msgs/Header.h> 4 #include <gtest/gtest.h> 7 TEST(LogUtils, testWarnNoRemap){
14 std::vector<std::string>
topics;
15 topics.push_back(std::string(
"~remap"));
18 EXPECT_EQ(
true, actual);
20 topics.push_back(std::string(
"~noremap"));
22 EXPECT_EQ(
false, actual);
25 TEST(LogUtils, testGetFunctionName){
26 std::string name = std::string(
27 "virtual void jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback(const ros::WallTimerEvent&)");
29 std::string expected = std::string(
"jsk_topic_tools::ConnectionBasedNodelet::warnNeverSubscribedCallback");
30 ASSERT_STREQ(expected.c_str(), actual.c_str());
33 TEST(LogUtils, testJSKROSXXX){
61 testing::InitGoogleTest(&argc, argv);
62 return RUN_ALL_TESTS();
#define JSK_ROS_WARN(str,...)
#define JSK_ROS_DEBUG_STREAM_THROTTLE(rate,...)
#define JSK_ROS_INFO_THROTTLE(rate, str,...)
#define JSK_ROS_DEBUG(str,...)
#define JSK_ROS_FATAL_STREAM(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define JSK_ROS_WARN_STREAM(...)
TEST(LogUtils, testWarnNoRemap)
#define JSK_ROS_INFO(str,...)
#define JSK_ROS_FATAL(str,...)
#define JSK_ROS_ERROR_STREAM(...)
#define JSK_ROS_FATAL_STREAM_THROTTLE(rate,...)
int main(int argc, char **argv)
#define JSK_ROS_DEBUG_STREAM(...)
#define JSK_ROS_ERROR_STREAM_THROTTLE(rate,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define JSK_ROS_INFO_STREAM_THROTTLE(rate,...)
#define JSK_ROS_DEBUG_THROTTLE(rate, str,...)
#define JSK_ROS_ERROR(str,...)
#define JSK_ROS_ERROR_THROTTLE(rate, str,...)
#define JSK_ROS_WARN_THROTTLE(rate, str,...)
#define JSK_ROS_WARN_STREAM_THROTTLE(rate,...)
#define JSK_ROS_INFO_STREAM(...)
#define JSK_ROS_FATAL_THROTTLE(rate, str,...)