subscribe_n_fast.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  * 
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* Author: Brian Gerkey */
00031 
00032 /*
00033  * Subscribe to a topic, expecting to get a single message.
00034  */
00035 
00036 #include <string>
00037 
00038 #include <gtest/gtest.h>
00039 
00040 #include <time.h>
00041 #include <stdlib.h>
00042 
00043 #include "ros/ros.h"
00044 #include <test_roscpp/TestArray.h>
00045 
00046 int g_argc;
00047 char** g_argv;
00048 
00049 class Subscriptions : public testing::Test
00050 {
00051   public:
00052     // A node is needed to make a service call
00053     ros::NodeHandle n;
00054     bool success;
00055     bool failure;
00056     std::string transport;
00057     bool reliable;
00058     int msgs_expected;
00059     int msgs_received;
00060     ros::Duration dt;
00061 
00062     void MsgCallback(const test_roscpp::TestArray::ConstPtr& msg)
00063     {
00064       if (failure || success)
00065         return;
00066 
00067       printf("received message %d\n", msg->counter);
00068       msgs_received++;
00069       if (reliable)
00070       {
00071         if (msgs_received != msg->counter)
00072         {
00073           failure = true;
00074           puts("failed");
00075         }
00076         if (msgs_received == (msgs_expected - 1))
00077         {
00078           success = true;
00079           puts("success");
00080         }
00081       }
00082       else
00083       {
00084         if (msgs_received > msg->counter)
00085         {
00086           failure = true;
00087           printf("failed: %d > %d\n", msgs_received, msg->counter);
00088         }
00089         if (msgs_received > (0.01 * msgs_expected))
00090         {
00091           success = true;
00092           puts("success");
00093         }
00094       }
00095 
00096     }
00097 
00098   protected:
00099     Subscriptions() {}
00100     void SetUp()
00101     {
00102       success = false;
00103       failure = false;
00104 
00105       msgs_received = -1;
00106       ASSERT_TRUE(g_argc == 4);
00107       transport = g_argv[1];
00108       msgs_expected = atoi(g_argv[2]);
00109       dt.fromSec(atof(g_argv[3]));
00110       if (transport == "tcp")
00111         reliable = true;
00112       else if (transport == "udp")
00113         reliable = false;
00114       else
00115       {
00116         ROS_ERROR("Unknown transport: %s", transport.c_str());
00117         FAIL();
00118       }
00119     }
00120     void TearDown()
00121     {
00122     }
00123 };
00124 
00125 TEST_F(Subscriptions, pubSubNFast)
00126 {
00127   ros::TransportHints hints;
00128   if (reliable)
00129     hints.reliable();
00130   else
00131     hints.unreliable();
00132 
00133   ros::Subscriber sub = n.subscribe("roscpp/pubsub_test", msgs_expected, &Subscriptions::MsgCallback, (Subscriptions *)this, hints);
00134   
00135   ASSERT_TRUE(sub);
00136 
00137   ros::Time t1(ros::Time::now() + dt);
00138   
00139   while(ros::Time::now() < t1 && !success)
00140   {
00141     ros::spinOnce();
00142     ros::WallDuration(0.01).sleep();
00143   }
00144   
00145   printf("msgs_received == %d\n", msgs_received);
00146   if(success)
00147     SUCCEED();
00148   else
00149     FAIL();
00150 }
00151 
00152 int
00153 main(int argc, char** argv)
00154 {
00155   testing::InitGoogleTest(&argc, argv);
00156   ros::init(argc, argv, "subscriber");
00157   g_argc = argc;
00158   g_argv = argv;
00159   return RUN_ALL_TESTS();
00160 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Thu Jun 6 2019 21:10:42