30 #include <gtest/gtest.h> 34 #include <std_msgs/Empty.h> 50 for (
auto i=0; i < num; ++i)
61 void emptyCb(
const std_msgs::EmptyConstPtr &msg)
68 bool connection_called =
false;
70 connection_called =
true;
82 EXPECT_TRUE(connection_called);
87 bool found_test_topic=
false;
88 for (
const auto &topic : doc_msg.topics)
90 if (topic.name ==
"test")
92 found_test_topic =
true;
95 EXPECT_TRUE(found_test_topic);
100 bool cb_called=
false;
101 auto empty_cb = [&cb_called](
const std_msgs::EmptyConstPtr &
msg){ cb_called =
true; };
111 empty_pub.
publish(boost::make_shared<std_msgs::Empty>());
114 EXPECT_TRUE(cb_called);
119 bool found_test_topic=
false;
120 for (
const auto &topic : doc_msg.topics)
122 if (topic.name ==
"test")
124 found_test_topic =
true;
127 EXPECT_TRUE(found_test_topic);
130 int main(
int argc,
char **argv)
132 ros::init(argc, argv,
"swri_node_handle_test");
133 testing::InitGoogleTest(&argc, argv);
134 int result = RUN_ALL_TESTS();
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publish(const boost::shared_ptr< M > &message) const
marti_introspection_msgs::NodeInfo getDocMsg() const
void emptyCb(const std_msgs::EmptyConstPtr &msg)
bool getEnableDocs() const
int main(int argc, char **argv)
ros::Subscriber subscribe(const std::string &name, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const std::string description, const ros::TransportHints &transport_hints=ros::TransportHints())
TEST_F(SwriNodeHandleTest, testConnectCbAdvertise)
void spinNumTimes(size_t num) const
ROSCPP_DECL void spinOnce()
ros::Publisher advertise(const std::string name, uint32_t queue_size, bool latched, const std::string description)