subscribe_resubscribe.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     bool success;
00053     bool failure;
00054     int msg_count;
00055     int msg_i;
00056     ros::Duration dt;
00057 
00058     void messageCallback(const test_roscpp::TestArrayConstPtr& msg)
00059     {
00060       if(failure || success)
00061         return;
00062 
00063       ROS_INFO("received message %d", msg->counter);
00064       msg_i++;
00065       if(msg_i != msg->counter)
00066       {
00067         failure = true;
00068         ROS_INFO("failed");
00069       }
00070       if(msg_i == (msg_count-1))
00071       {
00072         success = true;
00073         ROS_INFO("success");
00074       }
00075     }
00076 
00077   protected:
00078     Subscriptions() {}
00079     void SetUp()
00080     {
00081       success = false;
00082       failure = false;
00083 
00084       msg_i = -1;
00085       ASSERT_TRUE(g_argc == 3);
00086       msg_count = atoi(g_argv[1]);
00087       dt.fromSec(atof(g_argv[2]));
00088     }
00089     void TearDown()
00090     {
00091     }
00092 };
00093 
00094 TEST_F(Subscriptions, resubscribe)
00095 {
00096   ros::NodeHandle nh;
00097 
00098   {
00099     ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
00100     ASSERT_TRUE(sub);
00101     ros::Time t1(ros::Time::now()+dt);
00102 
00103     while(ros::Time::now() < t1 && !success)
00104     {
00105       ros::WallDuration(0.01).sleep();
00106       ros::spinOnce();
00107     }
00108   }
00109 
00110   if(!success)
00111     FAIL();
00112   else
00113   {
00114     success = false;
00115     failure = false;
00116     msg_i = -1;
00117 
00118     {
00119       ros::Subscriber sub = nh.subscribe("roscpp/pubsub_test2", 0, &Subscriptions::messageCallback, (Subscriptions*)this);
00120       ASSERT_TRUE(sub);
00121       ros::Time t1(ros::Time::now()+dt);
00122 
00123       while(ros::Time::now() < t1 && !success)
00124       {
00125         ros::WallDuration(0.01).sleep();
00126         ros::spinOnce();
00127       }
00128     }
00129 
00130     if(success)
00131       SUCCEED();
00132     else
00133       FAIL();
00134   }
00135 }
00136 
00137 int
00138 main(int argc, char** argv)
00139 {
00140   ros::init(argc, argv, "subscribe_resubscribe");
00141   ros::NodeHandle nh;
00142 
00143   testing::InitGoogleTest(&argc, argv);
00144   g_argc = argc;
00145   g_argv = argv;
00146   return RUN_ALL_TESTS();
00147 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:45:23