Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00029
00030 #include <ros/ros.h>
00031 #include <gtest/gtest.h>
00032
00033 #include <controller_manager_msgs/LoadController.h>
00034
00035 using namespace controller_manager_msgs;
00036
00037 TEST(CMTests, spawnTestGood)
00038 {
00039 ros::NodeHandle nh;
00040 ros::ServiceClient client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00041 LoadController srv;
00042 srv.request.name = "my_controller";
00043 bool call_success = client.call(srv);
00044 EXPECT_TRUE(call_success);
00045 EXPECT_TRUE(srv.response.ok);
00046 }
00047
00048 TEST(CMTests, spawnTestUnknown)
00049 {
00050 ros::NodeHandle nh;
00051 ros::ServiceClient client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00052 LoadController srv;
00053 srv.request.name = "nonexistient_controller";
00054 bool call_success = client.call(srv);
00055 EXPECT_TRUE(call_success);
00056 EXPECT_FALSE(srv.response.ok);
00057 }
00058
00059 TEST(CMTests, spawnTestMismatch)
00060 {
00061 ros::NodeHandle nh;
00062 ros::ServiceClient client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
00063 LoadController srv;
00064 srv.request.name = "dummy_controller";
00065 bool call_success = client.call(srv);
00066 EXPECT_TRUE(call_success);
00067 EXPECT_FALSE(srv.response.ok);
00068 }
00069
00070 int main(int argc, char** argv)
00071 {
00072 testing::InitGoogleTest(&argc, argv);
00073 ros::init(argc, argv, "ControllerManagerTestNode");
00074
00075 ros::AsyncSpinner spinner(1);
00076
00077
00078 ROS_INFO("Waiting for service");
00079 ros::service::waitForService("/controller_manager/load_controller");
00080 ROS_INFO("Start tests");
00081 spinner.start();
00082
00083 return RUN_ALL_TESTS();
00084 }