exercise_bond.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2009, 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 the 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 
00031 #include <bondcpp/bond.h>
00032 #include <gtest/gtest.h>
00033 #include <uuid/uuid.h>
00034 #include <ros/spinner.h>
00035 
00036 #include <test_bond/TestBond.h>
00037 
00038 #include <string>
00039 
00040 const char TOPIC[] = "test_bond_topic";
00041 
00042 std::string genId()
00043 {
00044   uuid_t uuid;
00045   uuid_generate_random(uuid);
00046   char uuid_str[40];
00047   uuid_unparse(uuid, uuid_str);
00048   return std::string(uuid_str);
00049 }
00050 
00051 ros::ServiceClient getService()
00052 {
00053   ros::NodeHandle nh;
00054   ros::ServiceClient cli = nh.serviceClient<test_bond::TestBond>("test_bond");
00055   EXPECT_TRUE(cli);
00056   EXPECT_TRUE(cli.waitForExistence(ros::Duration(5.0)));
00057   return cli;
00058 }
00059 
00060 TEST(ExerciseBondCpp, normal)
00061 {
00062   std::string id = genId();
00063   bond::Bond bond(TOPIC, id);
00064   ros::ServiceClient cli = getService();
00065   EXPECT_TRUE(cli.isValid());
00066   EXPECT_TRUE(cli.exists());
00067   test_bond::TestBond::Request req;
00068   test_bond::TestBond::Response resp;
00069   req.topic = TOPIC;
00070   req.id = id;
00071   req.delay_death = ros::Duration(2.0);
00072   ASSERT_TRUE(cli.call(req, resp));
00073   bond.start();
00074 
00075   EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00076   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00077 }
00078 
00079 TEST(ExerciseBondCpp, remoteNeverConnects)
00080 {
00081   std::string id = genId();
00082   // Never starts the other side of the bond
00083   bond::Bond bond(TOPIC, id);
00084   bond.start();
00085   EXPECT_FALSE(bond.waitUntilFormed(ros::Duration(1.0)));
00086   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(20.0)));
00087 }
00088 
00089 TEST(ExerciseBondCpp, heartbeatTimeout)
00090 {
00091   std::string id = genId();
00092   bond::Bond bond(TOPIC, id);
00093 
00094   ros::ServiceClient cli = getService();
00095   test_bond::TestBond::Request req;
00096   test_bond::TestBond::Response resp;
00097   req.topic = TOPIC;
00098   req.id = id;
00099   req.delay_death = ros::Duration(2.0);
00100   req.inhibit_death_message = true;
00101   ASSERT_TRUE(cli.call(req, resp));
00102 
00103   bond.start();
00104 
00105   EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00106   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(10.0)));
00107 }
00108 
00109 TEST(ExerciseBondCpp, cleanLocalDeath)
00110 {
00111   std::string id = genId();
00112   bond::Bond bond(TOPIC, id);
00113 
00114   ros::ServiceClient cli = getService();
00115   test_bond::TestBond::Request req;
00116   test_bond::TestBond::Response resp;
00117   req.topic = TOPIC;
00118   req.id = id;
00119   req.delay_death = ros::Duration(-1);
00120   ASSERT_TRUE(cli.call(req, resp));
00121 
00122   bond.start();
00123 
00124   EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00125   bond.breakBond();
00126   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00127 }
00128 
00129 TEST(ExerciseBondCpp, localDeathNoAck)
00130 {
00131   std::string id = genId();
00132   bond::Bond bond(TOPIC, id);
00133 
00134   ros::ServiceClient cli = getService();
00135   test_bond::TestBond::Request req;
00136   test_bond::TestBond::Response resp;
00137   req.topic = TOPIC;
00138   req.id = id;
00139   req.delay_death = ros::Duration(-1);
00140   req.inhibit_death_message = true;
00141   ASSERT_TRUE(cli.call(req, resp));
00142 
00143   bond.start();
00144 
00145   EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00146   bond.breakBond();
00147   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(5.0)));
00148 }
00149 
00150 TEST(ExerciseBondCpp, remoteIgnoresLocalDeath)
00151 {
00152   std::string id = genId();
00153   bond::Bond bond(TOPIC, id);
00154 
00155   ros::ServiceClient cli = getService();
00156   test_bond::TestBond::Request req;
00157   test_bond::TestBond::Response resp;
00158   req.topic = TOPIC;
00159   req.id = id;
00160   req.delay_death = ros::Duration(-1);
00161   req.inhibit_death = true;
00162   ASSERT_TRUE(cli.call(req, resp));
00163 
00164   bond.start();
00165 
00166   EXPECT_TRUE(bond.waitUntilFormed(ros::Duration(2.0)));
00167   bond.breakBond();
00168   EXPECT_FALSE(bond.waitUntilBroken(ros::Duration(1.0)));
00169   EXPECT_TRUE(bond.waitUntilBroken(ros::Duration(10.0)));
00170 }
00171 
00172 int main(int argc, char ** argv)
00173 {
00174   testing::InitGoogleTest(&argc, argv);
00175   ros::init(argc, argv, "exercise_bondcpp", true);
00176   ros::AsyncSpinner spinner(1);
00177   spinner.start();
00178   ros::NodeHandle nh;
00179   int ret = RUN_ALL_TESTS();
00180   spinner.stop();
00181   return ret;
00182 };


test_bond
Author(s): Stuart Glaser
autogenerated on Thu Jun 6 2019 20:40:42