trajectory_execution_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 
00030 #include <trajectory_execution_ros/trajectory_execution_monitor_ros.h>
00031 #include <planning_scene_monitor/planning_scene_monitor.h>
00032 #include <csignal>
00033 #include <gtest/gtest.h>
00034 #include <pr2_mechanism_msgs/ListControllers.h>
00035 
00036 boost::shared_ptr<trajectory_execution_ros::TrajectoryExecutionMonitorRos> emon;
00037 boost::shared_ptr<planning_scene_monitor::PlanningSceneMonitor> planning_scene_monitor_;
00038 ros::ServiceClient lister_service;
00039 
00040 void sigHandler(int x) {
00041   emon.reset();
00042   exit(0);
00043 }
00044 
00045 void getRunningControllerMap(std::map<std::string, bool>& controller_map) {
00046   controller_map.clear();
00047 
00048   pr2_mechanism_msgs::ListControllers::Request req;
00049   pr2_mechanism_msgs::ListControllers::Response res;
00050 
00051   if(!lister_service.call(req, res)) {
00052     ROS_WARN_STREAM("Something wrong with lister service");
00053     return;
00054   }
00055   for(unsigned int i = 0; i < res.controllers.size(); i++) {
00056     controller_map[res.controllers[i]] = (res.state[i] == "running");
00057   }
00058 }
00059 
00060 TEST(TrajectoryExecutionTests, loadUnload) {
00061 
00062   emon.reset(new trajectory_execution_ros::TrajectoryExecutionMonitorRos(planning_scene_monitor_->getPlanningScene()->getRobotModel()));
00063   std::map<std::string, bool> initial_map = emon->getOriginalControllerConfiguration();
00064   emon.reset();
00065   std::map<std::string, bool> after_map;
00066   getRunningControllerMap(after_map);
00067   ASSERT_EQ(after_map.size(), initial_map.size());
00068   std::map<std::string, bool>::iterator it2 = after_map.begin();
00069   for(std::map<std::string, bool>::iterator it = initial_map.begin();
00070       it != initial_map.end();
00071       it++, it2++) {
00072     EXPECT_EQ(it->first, it2->first);
00073     EXPECT_EQ(it->second, it2->second);
00074   }
00075 }
00076 
00077 TEST(TrajectoryExecutionTests, switchRestore) {
00078   emon.reset(new trajectory_execution_ros::TrajectoryExecutionMonitorRos(planning_scene_monitor_->getPlanningScene()->getRobotModel()));
00079   std::map<std::string, bool> initial_map = emon->getOriginalControllerConfiguration();
00080 
00081   EXPECT_TRUE(emon->getCurrentController("arms") == "r_arm_controller" ||
00082               emon->getCurrentController("arms") == "l_arm_controller");
00083   emon->switchAssociatedStopStartControllers("arms", "both_arms_controller");
00084 
00085   EXPECT_EQ(emon->getCurrentController("arms"), "both_arms_controller");
00086   EXPECT_EQ(emon->getCurrentController("right_arm"), "both_arms_controller");
00087   EXPECT_EQ(emon->getCurrentController("left_arm"), "both_arms_controller");
00088 
00089   emon->switchAssociatedStopStartControllers("right_arm", "r_arm_controller");
00090   //should be right arm, as that's what we replaced arms with
00091   EXPECT_EQ(emon->getCurrentController("arms"), "r_arm_controller");
00092   EXPECT_EQ(emon->getCurrentController("left_arm"), "l_arm_controller");
00093 
00094   emon->restoreOriginalControllers();
00095 
00096   std::map<std::string, bool> after_map;
00097   getRunningControllerMap(after_map);
00098   ASSERT_EQ(after_map.size(), initial_map.size());
00099   std::map<std::string, bool>::iterator it2 = after_map.begin();
00100   for(std::map<std::string, bool>::iterator it = initial_map.begin();
00101       it != initial_map.end();
00102       it++, it2++) {
00103     EXPECT_EQ(it->first, it2->first);
00104     EXPECT_EQ(it->second, it2->second);
00105   }
00106 }
00107 
00108 int main(int argc, char **argv)
00109 {
00110   ros::init(argc, argv, "trajectory_execution_tests", ros::init_options::NoSigintHandler);
00111   testing::InitGoogleTest(&argc, argv);
00112 
00113   signal(SIGINT, sigHandler);
00114   signal(SIGTERM, sigHandler);
00115 
00116   ros::NodeHandle nh;
00117 
00118   ros::service::waitForService("/pr2_controller_manager/list_controllers");
00119 
00120   planning_scene_monitor_.reset(new planning_scene_monitor::PlanningSceneMonitor("robot_description"));
00121   lister_service = nh.serviceClient<pr2_mechanism_msgs::ListControllers>("/pr2_controller_manager/list_controllers", true);
00122 
00123   int ret = RUN_ALL_TESTS();
00124 
00125   emon.reset();
00126 
00127   return ret;
00128 
00129   // ROS_INFO_STREAM("Current for arms is " << emon->getCurrentController("arms"));
00130 
00131   // //should switch to default controller for arms, stopping other two
00132   // emon->switchAssociatedStopStartControllers("arms", "both_arms_controller");
00133 
00134   // //sh
00135   // //emon->restoreToOriginalConfiguration();
00136 
00137   // ros::waitForShutdown();
00138 }


pr2_trajectory_execution_tests
Author(s): Gil Jones
autogenerated on Mon Oct 6 2014 11:15:05