Go to the documentation of this file.
30 #include <gmock/gmock.h>
32 #include <std_msgs/String.h>
49 rt_pub.
init(nh,
"construct_init_destruct", 10);
59 std::unique_lock<std::mutex> lock(
mtx_);
67 const std::chrono::milliseconds
DELAY(250);
69 const char * expected_msg =
"Hello World";
71 const bool latching =
true;
74 bool lock_is_held = rt_pub.
trylock();
75 for (
size_t i = 0; i <
ATTEMPTS && !lock_is_held; ++i)
77 lock_is_held = rt_pub.
trylock();
78 std::this_thread::sleep_for(
DELAY);
80 ASSERT_TRUE(lock_is_held);
81 rt_pub.
msg_.data = expected_msg;
88 for (
size_t i = 0; i <
ATTEMPTS && str_callback.
msg_.data.empty(); ++i)
91 std::this_thread::sleep_for(
DELAY);
93 EXPECT_STREQ(expected_msg, str_callback.
msg_.data.c_str());
96 int main(
int argc,
char ** argv) {
97 ::testing::InitGoogleTest(&argc, argv);
98 ros::init(argc, argv,
"realtime_publisher_tests");
99 return RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)
const std::chrono::milliseconds DELAY(250)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
TEST(RealtimePublisher, construct_destruct)
void callback(const std_msgs::String &msg)
realtime_tools
Author(s): Stuart Glaser
autogenerated on Mon Jan 8 2024 03:20:12