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), false);
00083 actionlib::SimpleActionServer<pr2_common_action_msgs::ArmMoveIKAction> ik_server(n, "r_arm_ik", boost::bind(&ik_execute, _1, &ik_server), false);
00084 actionlib::SimpleActionServer<pr2_plugs_msgs::DetectPlugOnBaseAction> plug_server(n, "detect_plug_on_base", boost::bind(&plug_execute, _1, &plug_server), false);
00085 actionlib::SimpleActionServer<pr2_controllers_msgs::Pr2GripperCommandAction> gripper_server(n, "r_gripper_controller/gripper_action", boost::bind(&gripper_execute, _1, &gripper_server), false);
00086 actionlib::SimpleActionServer<pr2_controllers_msgs::SingleJointPositionAction> spine_server(n, "torso_controller/position_joint_action", boost::bind(&spine_execute, _1, &spine_server), false);
00087 arm_server.start();
00088 ik_server.start();
00089 plug_server.start();
00090 gripper_server.start();
00091 spine_server.start();
00092
00093
00094 actionlib::SimpleActionClient<pr2_plugs_msgs::FetchPlugAction> ac("fetch_plug");
00095
00096
00097 EXPECT_TRUE(ac.waitForServer(ros::Duration(20.0)));
00098 ros::shutdown();
00099 spin_thread.join();
00100
00101 }
00102
00103 TEST(ActionServerTest, stow_plug)
00104 {
00105 ros::NodeHandle n;
00106 boost::thread spin_thread(&spinThread);
00107 actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> arm_server(n, "r_arm_controller/joint_trajectory_generator", boost::bind(&arm_execute, _1, &arm_server), false);
00108 actionlib::SimpleActionServer<pr2_common_action_msgs::ArmMoveIKAction> ik_server(n, "r_arm_ik", boost::bind(&ik_execute, _1, &ik_server), false);
00109 actionlib::SimpleActionServer<pr2_plugs_msgs::DetectPlugOnBaseAction> plug_server(n, "detect_plug_on_base", boost::bind(&plug_execute, _1, &plug_server), false);
00110 actionlib::SimpleActionServer<pr2_controllers_msgs::Pr2GripperCommandAction> gripper_server(n, "r_gripper_controller/gripper_action", boost::bind(&gripper_execute, _1, &gripper_server), false);
00111 actionlib::SimpleActionServer<pr2_controllers_msgs::SingleJointPositionAction> spine_server(n, "torso_controller/position_joint_action", boost::bind(&spine_execute, _1, &spine_server), false);
00112 arm_server.start();
00113 ik_server.start();
00114 plug_server.start();
00115 gripper_server.start();
00116 spine_server.start();
00117
00118 actionlib::SimpleActionClient<pr2_plugs_msgs::StowPlugAction> ac("stow_plug");
00119
00120
00121 EXPECT_TRUE(ac.waitForServer(ros::Duration(20.0)));
00122 ros::shutdown();
00123 spin_thread.join();
00124
00125 }
00126
00127 int main(int argc, char **argv){
00128 testing::InitGoogleTest(&argc, argv);
00129 ros::init(argc, argv, "fetch_and_stow_plug_tests");
00130 return RUN_ALL_TESTS();
00131
00132 }