cm_test.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2012, hiDOF INC.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of hiDOF Inc nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00030 
00031 #include <ros/ros.h>
00032 #include <gtest/gtest.h>
00033 
00034 #include <controller_manager_msgs/ListControllers.h>
00035 #include <controller_manager_msgs/ListControllerTypes.h>
00036 #include <controller_manager_msgs/LoadController.h>
00037 #include <controller_manager_msgs/SwitchController.h>
00038 #include <controller_manager_msgs/UnloadController.h>
00039 
00040 
00041 using namespace controller_manager_msgs;
00042 
00043 TEST(CMTests, loadUnloadOk)
00044 {
00045   ros::NodeHandle nh;
00046   ros::ServiceClient load_client   = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00047   ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
00048 
00049   // Load single-interface controller
00050   {
00051     LoadController srv;
00052     srv.request.name = "my_controller";
00053     bool call_success = load_client.call(srv);
00054     ASSERT_TRUE(call_success);
00055     EXPECT_TRUE(srv.response.ok);
00056   }
00057 
00058   // Load multi-interface controller:
00059   // Two required interfaces
00060   {
00061     LoadController srv;
00062     srv.request.name = "vel_eff_controller";
00063     bool call_success = load_client.call(srv);
00064     ASSERT_TRUE(call_success);
00065     EXPECT_TRUE(srv.response.ok);
00066   }
00067 
00068   // Load multi-interface controller:
00069   // One required (and existing) interface and one optional (and non-existent) interface
00070   {
00071     LoadController srv;
00072     srv.request.name = "optional_interfaces_controller";
00073     bool call_success = load_client.call(srv);
00074     ASSERT_TRUE(call_success);
00075     EXPECT_TRUE(srv.response.ok);
00076   }
00077 
00078   // Unload single-interface controller
00079   {
00080     UnloadController srv;
00081     srv.request.name = "my_controller";
00082     bool call_success = unload_client.call(srv);
00083     ASSERT_TRUE(call_success);
00084     EXPECT_TRUE(srv.response.ok);
00085   }
00086 
00087   // Unload multi-interface controllers
00088   {
00089     UnloadController srv;
00090     srv.request.name = "vel_eff_controller";
00091     bool call_success = unload_client.call(srv);
00092     ASSERT_TRUE(call_success);
00093     EXPECT_TRUE(srv.response.ok);
00094   }
00095   {
00096     UnloadController srv;
00097     srv.request.name = "optional_interfaces_controller";
00098     bool call_success = unload_client.call(srv);
00099     ASSERT_TRUE(call_success);
00100     EXPECT_TRUE(srv.response.ok);
00101   }
00102 }
00103 
00104 TEST(CMTests, loadUnloadKo)
00105 {
00106   ros::NodeHandle nh;
00107   ros::ServiceClient load_client   = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00108   ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
00109 
00110   // Load non-existent controller
00111   {
00112     LoadController srv;
00113     srv.request.name = "nonexistent_controller";
00114     bool call_success = load_client.call(srv);
00115     ASSERT_TRUE(call_success);
00116     EXPECT_FALSE(srv.response.ok);
00117   }
00118 
00119   // Load controller requesting non-existient HW interface
00120   {
00121     LoadController srv;
00122     srv.request.name = "non_existent_interface_controller";
00123     bool call_success = load_client.call(srv);
00124     ASSERT_TRUE(call_success);
00125     EXPECT_FALSE(srv.response.ok);
00126   }
00127 
00128   // Load controller requesting non-existent resource from valid HW interface
00129   {
00130     LoadController srv;
00131     srv.request.name = "non_existent_resource_controller";
00132     bool call_success = load_client.call(srv);
00133     ASSERT_TRUE(call_success);
00134     EXPECT_FALSE(srv.response.ok);
00135   }
00136 
00137   // Load multi-interface controller:
00138   // Two required HW interfaces, of which one is non-existent
00139   {
00140     LoadController srv;
00141     srv.request.name = "non_existing_multi_interface_controller";
00142     bool call_success = load_client.call(srv);
00143     ASSERT_TRUE(call_success);
00144     EXPECT_FALSE(srv.response.ok);
00145   }
00146 
00147   // Unload not loaded controller
00148   {
00149     UnloadController srv;
00150     srv.request.name = "my_controller";
00151     bool call_success = unload_client.call(srv);
00152     ASSERT_TRUE(call_success);
00153     EXPECT_FALSE(srv.response.ok);
00154   }
00155 }
00156 
00157 TEST(CMTests, switchController)
00158 {
00159   ros::NodeHandle nh;
00160   ros::ServiceClient load_client   = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00161   ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
00162   ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
00163 
00164   // Load controllers
00165   {
00166     LoadController srv;
00167     srv.request.name = "my_controller";
00168     load_client.call(srv);
00169     srv.request.name = "my_controller2";
00170     load_client.call(srv);
00171     srv.request.name = "vel_eff_controller";
00172     load_client.call(srv);
00173   }
00174 
00175   // Successful STRICT start
00176   {
00177     SwitchController srv;
00178     srv.request.start_controllers.push_back("my_controller");
00179     srv.request.strictness = srv.request.STRICT;
00180     bool call_success = switch_client.call(srv);
00181     ASSERT_TRUE(call_success);
00182     EXPECT_TRUE(srv.response.ok);
00183   }
00184 
00185   // Successful STRICT stop
00186   {
00187     SwitchController srv;
00188     srv.request.stop_controllers.push_back("my_controller");
00189     srv.request.strictness = srv.request.STRICT;
00190     bool call_success = switch_client.call(srv);
00191     ASSERT_TRUE(call_success);
00192     EXPECT_TRUE(srv.response.ok);
00193   }
00194 
00195   // Successful STRICT start
00196   {
00197     SwitchController srv;
00198     srv.request.start_controllers.push_back("vel_eff_controller");
00199     srv.request.strictness = srv.request.STRICT;
00200     bool call_success = switch_client.call(srv);
00201     ASSERT_TRUE(call_success);
00202     EXPECT_TRUE(srv.response.ok);
00203   }
00204 
00205   // Successful STRICT stop+start
00206   {
00207     SwitchController srv;
00208     srv.request.start_controllers.push_back("my_controller");
00209     srv.request.stop_controllers.push_back("vel_eff_controller");
00210     srv.request.strictness = srv.request.STRICT;
00211     bool call_success = switch_client.call(srv);
00212     ASSERT_TRUE(call_success);
00213     EXPECT_TRUE(srv.response.ok);
00214   }
00215 
00216   // Back to no running controllers
00217   {
00218     SwitchController srv;
00219     srv.request.stop_controllers.push_back("my_controller");
00220     srv.request.strictness = srv.request.STRICT;
00221     bool call_success = switch_client.call(srv);
00222     ASSERT_TRUE(call_success);
00223     EXPECT_TRUE(srv.response.ok);
00224   }
00225 
00226   // Unsuccessful STRICT start
00227   {
00228     SwitchController srv;
00229     srv.request.start_controllers.push_back("non_existent_controller");
00230     srv.request.strictness = srv.request.STRICT;
00231     bool call_success = switch_client.call(srv);
00232     ASSERT_TRUE(call_success);
00233     EXPECT_FALSE(srv.response.ok);
00234   }
00235 
00236   // Unsuccessful STRICT stop
00237   {
00238     SwitchController srv;
00239     srv.request.stop_controllers.push_back("non_existent_controller");
00240     srv.request.strictness = srv.request.STRICT;
00241     bool call_success = switch_client.call(srv);
00242     ASSERT_TRUE(call_success);
00243     EXPECT_FALSE(srv.response.ok);
00244   }
00245 
00246   // Unsuccessful STRICT switch: invalid stop
00247   {
00248     SwitchController srv;
00249     srv.request.start_controllers.push_back("my_controller");
00250     srv.request.stop_controllers.push_back("non_existent_controller");
00251     srv.request.strictness = srv.request.STRICT;
00252     bool call_success = switch_client.call(srv);
00253     ASSERT_TRUE(call_success);
00254     EXPECT_FALSE(srv.response.ok);
00255   }
00256 
00257   // Unsuccessful STRICT switch: invalid start
00258   {
00259     SwitchController srv;
00260     srv.request.start_controllers.push_back("non_existent_controller");
00261     srv.request.stop_controllers.push_back("my_controller");
00262     srv.request.strictness = srv.request.STRICT;
00263     bool call_success = switch_client.call(srv);
00264     ASSERT_TRUE(call_success);
00265     EXPECT_FALSE(srv.response.ok);
00266   }
00267 
00268   // Unsuccessful STRICT start: Resource conflict within single controller
00269   {
00270     SwitchController srv;
00271     srv.request.start_controllers.push_back("self_conflict_controller");
00272     srv.request.strictness = srv.request.STRICT;
00273     bool call_success = switch_client.call(srv);
00274     ASSERT_TRUE(call_success);
00275     EXPECT_FALSE(srv.response.ok);
00276   }
00277 
00278   // Unsuccessful STRICT start: Resource conflict between two controllers
00279   {
00280     SwitchController srv;
00281     srv.request.start_controllers.push_back("my_controller");
00282     srv.request.start_controllers.push_back("my_controller2");
00283     srv.request.strictness = srv.request.STRICT;
00284     bool call_success = switch_client.call(srv);
00285     ASSERT_TRUE(call_success);
00286     EXPECT_FALSE(srv.response.ok);
00287   }
00288 
00289   // Successful BEST_EFFORT switch: No-op
00290   {
00291       SwitchController srv;
00292       srv.request.start_controllers.push_back("non_existent_controller");
00293       srv.request.stop_controllers.push_back("non_existent_controller");
00294       srv.request.strictness = srv.request.BEST_EFFORT;
00295       bool call_success = switch_client.call(srv);
00296       ASSERT_TRUE(call_success);
00297       EXPECT_TRUE(srv.response.ok);
00298   }
00299 
00300   // Successful BEST_EFFORT switch: Partial success, only one started controller
00301   {
00302       SwitchController srv;
00303       srv.request.start_controllers.push_back("my_controller2");
00304       srv.request.start_controllers.push_back("non_existent_controller");
00305       srv.request.stop_controllers.push_back("non_existent_controller");
00306       srv.request.stop_controllers.push_back("my_controller");
00307       srv.request.strictness = srv.request.BEST_EFFORT;
00308       bool call_success = switch_client.call(srv);
00309       ASSERT_TRUE(call_success);
00310       EXPECT_TRUE(srv.response.ok);
00311   }
00312 
00313   // Successful BEST_EFFORT switch: Partial success, one started and one stopped controller
00314   {
00315       SwitchController srv;
00316       srv.request.start_controllers.push_back("my_controller");
00317       srv.request.start_controllers.push_back("non_existent_controller");
00318       srv.request.stop_controllers.push_back("non_existent_controller");
00319       srv.request.stop_controllers.push_back("my_controller2");
00320       srv.request.strictness = srv.request.BEST_EFFORT;
00321       bool call_success = switch_client.call(srv);
00322       ASSERT_TRUE(call_success);
00323       EXPECT_TRUE(srv.response.ok);
00324   }
00325 
00326   // Back to no running controllers
00327   {
00328     SwitchController srv;
00329     srv.request.stop_controllers.push_back("my_controller");
00330     srv.request.strictness = srv.request.STRICT;
00331     bool call_success = switch_client.call(srv);
00332     ASSERT_TRUE(call_success);
00333     EXPECT_TRUE(srv.response.ok);
00334   }
00335 
00336   // Unload controllers
00337   {
00338     UnloadController srv;
00339     srv.request.name = "my_controller";
00340     unload_client.call(srv);
00341     srv.request.name = "my_controller2";
00342     unload_client.call(srv);
00343     srv.request.name = "vel_eff_controller";
00344     unload_client.call(srv);
00345   }
00346 }
00347 
00348 TEST(CMTests, stopBeforeUnload)
00349 {
00350   ros::NodeHandle nh;
00351   ros::ServiceClient load_client   = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00352   ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
00353   ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
00354 
00355   // Load controller
00356   {
00357     LoadController srv;
00358     srv.request.name = "my_controller";
00359     bool call_success = load_client.call(srv);
00360     ASSERT_TRUE(call_success);
00361     EXPECT_TRUE(srv.response.ok);
00362   }
00363 
00364   // Start controller
00365   {
00366     SwitchController srv;
00367     srv.request.start_controllers.push_back("my_controller");
00368     srv.request.strictness = srv.request.STRICT;
00369     bool call_success = switch_client.call(srv);
00370     ASSERT_TRUE(call_success);
00371     EXPECT_TRUE(srv.response.ok);
00372   }
00373 
00374   // Try to unload running controller and fail
00375   {
00376     UnloadController srv;
00377     srv.request.name = "my_controller";
00378     bool call_success = unload_client.call(srv);
00379     ASSERT_TRUE(call_success);
00380     EXPECT_FALSE(srv.response.ok);
00381   }
00382 
00383   // Stop controller
00384   {
00385     SwitchController srv;
00386     srv.request.stop_controllers.push_back("my_controller");
00387     srv.request.strictness = srv.request.STRICT;
00388     bool call_success = switch_client.call(srv);
00389     ASSERT_TRUE(call_success);
00390     EXPECT_TRUE(srv.response.ok);
00391   }
00392 
00393   // Unload stopped controller
00394   {
00395     UnloadController srv;
00396     srv.request.name = "my_controller";
00397     bool call_success = unload_client.call(srv);
00398     ASSERT_TRUE(call_success);
00399     EXPECT_TRUE(srv.response.ok);
00400   }
00401 }
00402 
00403 TEST(CMTests, listControllerTypes)
00404 {
00405   ros::NodeHandle nh;
00406   ros::ServiceClient types_client = nh.serviceClient<ListControllerTypes>("/controller_manager/list_controller_types");
00407 
00408   ListControllerTypes srv;
00409   bool call_success = types_client.call(srv);
00410   ASSERT_TRUE(call_success);
00411   // Weak test that the number of available types and base classes is not lower than those defined in this test package
00412   EXPECT_GE(srv.response.types.size(), 3);
00413   EXPECT_GE(srv.response.base_classes.size(), 3);
00414 }
00415 
00416 TEST(CMTests, listControllers)
00417 {
00418   ros::NodeHandle nh;
00419   ros::ServiceClient load_client   = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00420   ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
00421   ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
00422   ros::ServiceClient list_client   = nh.serviceClient<ListControllers>("/controller_manager/list_controllers");
00423 
00424   // Load controllers
00425   {
00426     LoadController srv;
00427     srv.request.name = "my_controller";
00428     load_client.call(srv);
00429     srv.request.name = "vel_eff_controller";
00430     load_client.call(srv);
00431   }
00432 
00433   // Start one controller
00434   {
00435     SwitchController srv;
00436     srv.request.start_controllers.push_back("my_controller");
00437     srv.request.strictness = srv.request.STRICT;
00438     switch_client.call(srv);
00439   }
00440 
00441   // List controllers
00442   {
00443     ListControllers srv;
00444     bool call_success = list_client.call(srv);
00445     ASSERT_TRUE(call_success);
00446     ASSERT_EQ(srv.response.controller.size(), 2);
00447 
00448     ControllerState state1, state2;
00449     if (srv.response.controller[0].name == "my_controller")
00450     {
00451       state1 = srv.response.controller[0];
00452       state2 = srv.response.controller[1];
00453     }
00454     else
00455     {
00456       state1 = srv.response.controller[1];
00457       state2 = srv.response.controller[0];
00458     }
00459 
00460     EXPECT_EQ(state1.name, "my_controller");
00461     EXPECT_EQ(state1.state, "running");
00462     EXPECT_EQ(state1.type, "controller_manager_tests/EffortTestController");
00463     ASSERT_EQ(state1.claimed_resources.size(), 1);
00464     EXPECT_EQ(state1.claimed_resources[0].hardware_interface, "hardware_interface::EffortJointInterface");
00465     ASSERT_EQ(state1.claimed_resources[0].resources.size(), 2);
00466     EXPECT_EQ(state1.claimed_resources[0].resources[0], "hiDOF_joint1");
00467     EXPECT_EQ(state1.claimed_resources[0].resources[1], "hiDOF_joint2");
00468 
00469     EXPECT_EQ(state2.name, "vel_eff_controller");
00470     EXPECT_EQ(state2.state, "stopped");
00471     EXPECT_EQ(state2.type, "controller_manager_tests/VelEffController");
00472     EXPECT_EQ(state2.claimed_resources.size(), 2);
00473     EXPECT_EQ(state2.claimed_resources[0].hardware_interface, "hardware_interface::VelocityJointInterface");
00474     ASSERT_EQ(state2.claimed_resources[0].resources.size(), 2);
00475     EXPECT_EQ(state2.claimed_resources[0].resources[0], "hiDOF_joint1");
00476     EXPECT_EQ(state2.claimed_resources[0].resources[1], "hiDOF_joint2");
00477     EXPECT_EQ(state2.claimed_resources[1].hardware_interface, "hardware_interface::EffortJointInterface");
00478     ASSERT_EQ(state2.claimed_resources[1].resources.size(), 1);
00479     EXPECT_EQ(state2.claimed_resources[1].resources[0], "hiDOF_joint3");
00480   }
00481 
00482   // Stop running controller
00483   {
00484     SwitchController srv;
00485     srv.request.stop_controllers.push_back("my_controller");
00486     srv.request.strictness = srv.request.STRICT;
00487     switch_client.call(srv);
00488   }
00489 
00490   // Unload controllers
00491   {
00492     UnloadController srv;
00493     srv.request.name = "my_controller";
00494     unload_client.call(srv);
00495     srv.request.name = "vel_eff_controller";
00496     unload_client.call(srv);
00497   }
00498 }
00499 
00500 int main(int argc, char** argv)
00501 {
00502   testing::InitGoogleTest(&argc, argv);
00503   ros::init(argc, argv, "ControllerManagerTestNode");
00504 
00505   ros::AsyncSpinner spinner(1);
00506 
00507   // wait for services
00508   ROS_INFO("Waiting for service");
00509   ros::service::waitForService("/controller_manager/load_controller");
00510   ROS_INFO("Start tests");
00511   spinner.start();
00512   int ret = RUN_ALL_TESTS();
00513   spinner.stop();
00514   ros::shutdown();
00515   return ret;
00516 }


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:03