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
00026
00027
00028
00029
00030
00031
00032
00033 #include <ros/ros.h>
00034 #include <gtest/gtest.h>
00035 #include <boost/thread.hpp>
00036 #include <actionlib/client/simple_action_client.h>
00037 #include <pr2_plugs_msgs/DetectPlugInGripperAction.h>
00038 #include <pr2_plugs_msgs/VisionPlugDetectionAction.h>
00039 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00040 #include <actionlib/server/simple_action_server.h>
00041
00042
00043 void spinThread()
00044 {
00045 ros::spin();
00046 }
00047
00048 void arm_execute(const pr2_controllers_msgs::JointTrajectoryGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction>* as)
00049 {
00050 as->setSucceeded();
00051 }
00052
00053 void plug_execute(const pr2_plugs_msgs::VisionPlugDetectionGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_plugs_msgs::VisionPlugDetectionAction>* as)
00054 {
00055 as->setSucceeded();
00056 }
00057
00058
00059 TEST(ActionServerTest, detect_plug)
00060 {
00061 ros::NodeHandle n;
00062 actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> arm_server(n, "r_arm_controller/joint_trajectory_generator", boost::bind(&arm_execute, _1, &arm_server));
00063 actionlib::SimpleActionServer<pr2_plugs_msgs::VisionPlugDetectionAction> plug_server(n, "vision_plug_detection", boost::bind(&plug_execute, _1, &plug_server));
00064
00065 actionlib::SimpleActionClient<pr2_plugs_msgs::DetectPlugInGripperAction> ac("detect_plug");
00066
00067 boost::thread spin_thread(&spinThread);
00068 EXPECT_TRUE(ac.waitForServer(ros::Duration(15.0)));
00069 ros::shutdown();
00070 spin_thread.join();
00071
00072 }
00073
00074 int main(int argc, char **argv){
00075 testing::InitGoogleTest(&argc, argv);
00076 ros::init(argc, argv, "detect_plug_tests");
00077 return RUN_ALL_TESTS();
00078
00079 }