$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 * 00029 * Author: Melonee Wise 00030 */ 00031 00032 #include <ros/ros.h> 00033 #include <gtest/gtest.h> 00034 #include <pr2_plugs_common/joint_space_move.h> 00035 #include <pr2_controllers_msgs/JointTrajectoryAction.h> 00036 #include <actionlib/server/simple_action_server.h> 00037 #include <boost/thread.hpp> 00038 00039 typedef actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> Server; 00040 00041 void execute(const pr2_controllers_msgs::JointTrajectoryGoalConstPtr& goal, Server* as) 00042 { 00043 double joint_pos[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0}; 00044 std::vector<double> pos (joint_pos, joint_pos + sizeof(joint_pos) / sizeof(double) ); 00045 if(goal->trajectory.points[0].positions == pos) 00046 as->setSucceeded(); 00047 else 00048 as->setAborted(); 00049 } 00050 00051 void spinThread() 00052 { 00053 ros::spin(); 00054 } 00055 00056 00057 TEST(JointSpaceMove, test_failure) 00058 { 00059 00060 EXPECT_TRUE(pr2_plugs_common::gotoJointPosition(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, true)); 00061 00062 } 00063 00064 int main(int argc, char **argv){ 00065 testing::InitGoogleTest(&argc, argv); 00066 ros::init(argc, argv, "trajectory_unwrap_test"); 00067 ros::NodeHandle n; 00068 Server server(n, "r_arm_controller/joint_trajectory_action", boost::bind(&execute, _1, &server)); 00069 boost::thread spin_thread(&spinThread); 00070 int log = RUN_ALL_TESTS(); 00071 ros::shutdown(); 00072 spin_thread.join(); 00073 return log; 00074 00075 }