35 #include <gtest/gtest.h>    41 #include <std_msgs/UInt32.h>    43 #include <boost/thread.hpp>    45 using namespace rosrt;
    53   void cb(
const std_msgs::UInt32ConstPtr& msg)
    74   std_msgs::UInt32Ptr msg = pub.
allocate();
    86   ASSERT_EQ(h.
count, 1UL);
    87   ASSERT_EQ(h.
latest->data, 5UL);
   100   static const uint32_t count = 100;
   106   for (uint32_t i = 0; i < count; ++i)
   108     std::stringstream topic;
   109     topic << 
"test" << i;
   110     pubs[i].
initialize(nh.
advertise<std_msgs::UInt32>(topic.str(), 0), 100, std_msgs::UInt32());
   114   for (uint32_t j = 0; j < 100; ++j)
   116     for (uint32_t i = 0; i < count; ++i)
   118       std_msgs::UInt32Ptr msg = pubs[i].
allocate();
   121       ASSERT_TRUE(pubs[i].
publish(msg));
   125   uint32_t recv_count = 0;
   126   while (recv_count < count * 100)
   133     for (uint32_t i = 0; i < count; ++i)
   135       recv_count += helpers[i].
count;
   139   ASSERT_EQ(recv_count, count * 100);
   141   for (uint32_t i = 0; i < count; ++i)
   143     ASSERT_EQ(helpers[i].latest->data, 99UL);
   151     std_msgs::UInt32Ptr msg = pub.
allocate();
   167   static const uint32_t count = 10;
   173   boost::thread_group tg;
   175   for (uint32_t i = 0; i < count; ++i)
   177     std::stringstream topic;
   178     topic << 
"test" << i;
   179     pubs[i].
initialize(nh.
advertise<std_msgs::UInt32>(topic.str(), 0), 100, std_msgs::UInt32());
   182     tg.create_thread(boost::bind(
publishThread, boost::ref(pubs[i]), boost::ref(done)));
   185   uint32_t recv_count = 0;
   186   while (recv_count < count * 10000)
   192     for (uint32_t i = 0; i < count; ++i)
   194       recv_count += helpers[i].
count;
   203   ASSERT_GE(recv_count, count * 10000);
   205   for (uint32_t i = 0; i < count; ++i)
   207     ASSERT_TRUE(helpers[i].latest);
   211 int main(
int argc, 
char** argv)
   213   ros::init(argc, argv, 
"test_rt_publisher");
   214   testing::InitGoogleTest(&argc, argv);
   219   return RUN_ALL_TESTS();
 AllocInfo getThreadAllocInfo()
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 publishThread(Publisher< std_msgs::UInt32 > &pub, bool &done)
void init(const InitOptions &ops=InitOptions())
int main(int argc, char **argv)
a realtime-safe ROS publisher 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cb(const std_msgs::UInt32ConstPtr &msg)
bool publish(const ros::Publisher &pub, const VoidConstPtr &msg, PublishFunc pub_func, CloneFunc clone_func)
void resetThreadAllocInfo()
std_msgs::UInt32ConstPtr latest
void initialize(const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
initialization function. Only use with the default constructor 
ROSCPP_DECL void spinOnce()
boost::shared_ptr< M > allocate()
Allocate a message. The message will have been constructed with the template provided to initialize()...
bool publish(const MConstPtr &msg)
Publish a message. 
TEST(Publisher, singlePublisher)