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/FetchPlugAction.h>
00038 #include <pr2_plugs_msgs/StowPlugAction.h>
00039 #include <pr2_plugs_msgs/DetectPlugOnBaseAction.h>
00040 #include <pr2_controllers_msgs/SingleJointPositionAction.h>
00041 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00042 #include <pr2_controllers_msgs/Pr2GripperCommandAction.h>
00043 #include <pr2_common_action_msgs/ArmMoveIKAction.h>
00044 #include <actionlib/server/simple_action_server.h>
00045
00046
00047 void spinThread()
00048 {
00049 ros::spin();
00050 }
00051
00052 void arm_execute(const pr2_controllers_msgs::JointTrajectoryGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction>* as)
00053 {
00054 as->setSucceeded();
00055 }
00056
00057 void gripper_execute(const pr2_controllers_msgs::Pr2GripperCommandGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_controllers_msgs::Pr2GripperCommandAction>* as)
00058 {
00059 as->setSucceeded();
00060 }
00061
00062 void ik_execute(const pr2_common_action_msgs::ArmMoveIKGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_common_action_msgs::ArmMoveIKAction>* as)
00063 {
00064 as->setSucceeded();
00065 }
00066
00067 void plug_execute(const pr2_plugs_msgs::DetectPlugOnBaseGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_plugs_msgs::DetectPlugOnBaseAction>* as)
00068 {
00069 as->setSucceeded();
00070 }
00071
00072 void spine_execute(const pr2_controllers_msgs::SingleJointPositionGoalConstPtr& goal, actionlib::SimpleActionServer<pr2_controllers_msgs::SingleJointPositionAction>* as)
00073 {
00074 as->setSucceeded();
00075 }
00076
00077
00078 TEST(ActionServerTest, fetch_plug)
00079 {
00080 ros::NodeHandle n;
00081 boost::thread spin_thread(&spinThread);
00082 actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> arm_server(n, "r_arm_controller/joint_trajectory_generator", boost::bind(&arm_execute, _1, &arm_server));
00083 actionlib::SimpleActionServer<pr2_common_action_msgs::ArmMoveIKAction> ik_server(n, "r_arm_ik", boost::bind(&ik_execute, _1, &ik_server));
00084 actionlib::SimpleActionServer<pr2_plugs_msgs::DetectPlugOnBaseAction> plug_server(n, "detect_plug_on_base", boost::bind(&plug_execute, _1, &plug_server));
00085 actionlib::SimpleActionServer<pr2_controllers_msgs::Pr2GripperCommandAction> gripper_server(n, "r_gripper_controller/gripper_action", boost::bind(&gripper_execute, _1, &gripper_server));
00086 actionlib::SimpleActionServer<pr2_controllers_msgs::SingleJointPositionAction> spine_server(n, "torso_controller/position_joint_action", boost::bind(&spine_execute, _1, &spine_server));
00087
00088
00089 actionlib::SimpleActionClient<pr2_plugs_msgs::FetchPlugAction> ac("fetch_plug");
00090
00091
00092 EXPECT_TRUE(ac.waitForServer(ros::Duration(20.0)));
00093 ros::shutdown();
00094 spin_thread.join();
00095
00096 }
00097
00098 TEST(ActionServerTest, stow_plug)
00099 {
00100 ros::NodeHandle n;
00101 boost::thread spin_thread(&spinThread);
00102 actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> arm_server(n, "r_arm_controller/joint_trajectory_generator", boost::bind(&arm_execute, _1, &arm_server));
00103 actionlib::SimpleActionServer<pr2_common_action_msgs::ArmMoveIKAction> ik_server(n, "r_arm_ik", boost::bind(&ik_execute, _1, &ik_server));
00104 actionlib::SimpleActionServer<pr2_plugs_msgs::DetectPlugOnBaseAction> plug_server(n, "detect_plug_on_base", boost::bind(&plug_execute, _1, &plug_server));
00105 actionlib::SimpleActionServer<pr2_controllers_msgs::Pr2GripperCommandAction> gripper_server(n, "r_gripper_controller/gripper_action", boost::bind(&gripper_execute, _1, &gripper_server));
00106 actionlib::SimpleActionServer<pr2_controllers_msgs::SingleJointPositionAction> spine_server(n, "torso_controller/position_joint_action", boost::bind(&spine_execute, _1, &spine_server));
00107
00108 actionlib::SimpleActionClient<pr2_plugs_msgs::StowPlugAction> ac("stow_plug");
00109
00110
00111 EXPECT_TRUE(ac.waitForServer(ros::Duration(20.0)));
00112 ros::shutdown();
00113 spin_thread.join();
00114
00115 }
00116
00117 int main(int argc, char **argv){
00118 testing::InitGoogleTest(&argc, argv);
00119 ros::init(argc, argv, "fetch_and_stow_plug_tests");
00120 return RUN_ALL_TESTS();
00121
00122 }