test_moveit_controller_manager.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef TEST_MOVEIT_CONTROLLER_MANAGER_
00036 #define TEST_MOVEIT_CONTROLLER_MANAGER_
00037 
00038 #include <moveit/controller_manager/controller_manager.h>
00039 
00040 namespace test_moveit_controller_manager
00041 {
00042 
00043 class TestMoveItControllerHandle : public moveit_controller_manager::MoveItControllerHandle
00044 {
00045 public:
00046 
00047   TestMoveItControllerHandle(const std::string &name) : MoveItControllerHandle(name)
00048   {
00049   }
00050 
00051   virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &trajectory)
00052   {
00053     return true;
00054   }
00055 
00056   virtual bool cancelExecution()
00057   {
00058     return true;
00059   }
00060 
00061   virtual bool waitForExecution(const ros::Duration &timeout = ros::Duration(0))
00062   {
00063     return false;
00064   }
00065 
00066   virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
00067   {
00068     return moveit_controller_manager::ExecutionStatus::SUCCEEDED;
00069   }
00070 
00071 };
00072 
00073 class TestMoveItControllerManager : public moveit_controller_manager::MoveItControllerManager
00074 {
00075 public:
00076   static const int ACTIVE = 1;
00077   static const int DEFAULT = 2;
00078 
00079   TestMoveItControllerManager()
00080   {
00081     controllers_["right_arm"] = DEFAULT;
00082     controllers_["left_arm"] = ACTIVE + DEFAULT;
00083     controllers_["arms"] = 0;
00084     controllers_["base"] = DEFAULT;
00085     controllers_["head"] = 0;
00086     controllers_["left_arm_head"] = 0;
00087 
00088     controller_joints_["right_arm"].push_back("rj1");
00089     controller_joints_["right_arm"].push_back("rj2");
00090 
00091     controller_joints_["left_arm"].push_back("lj1");
00092     controller_joints_["left_arm"].push_back("lj2");
00093     controller_joints_["left_arm"].push_back("lj3");
00094 
00095     controller_joints_["arms"].insert(controller_joints_["arms"].end(), controller_joints_["left_arm"].begin(), controller_joints_["left_arm"].end());
00096     controller_joints_["arms"].insert(controller_joints_["arms"].end(), controller_joints_["right_arm"].begin(), controller_joints_["right_arm"].end());
00097 
00098     controller_joints_["base"].push_back("basej");
00099     controller_joints_["head"].push_back("headj");
00100 
00101     controller_joints_["left_arm_head"].insert(controller_joints_["left_arm_head"].end(), controller_joints_["left_arm"].begin(), controller_joints_["left_arm"].end());
00102     controller_joints_["left_arm_head"].insert(controller_joints_["left_arm_head"].end(), controller_joints_["head"].begin(), controller_joints_["head"].end());
00103   }
00104 
00105   virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
00106   {
00107     return moveit_controller_manager::MoveItControllerHandlePtr(new TestMoveItControllerHandle(name));
00108   }
00109 
00110   virtual void getControllersList(std::vector<std::string> &names)
00111   {
00112     names.clear();
00113     for (std::map<std::string, int>::const_iterator it = controllers_.begin() ; it != controllers_.end() ; ++it)
00114       names.push_back(it->first);
00115   }
00116 
00117   virtual void getActiveControllers(std::vector<std::string> &names)
00118   {
00119     names.clear();
00120     for (std::map<std::string, int>::const_iterator it = controllers_.begin() ; it != controllers_.end() ; ++it)
00121       if (it->second & ACTIVE)
00122         names.push_back(it->first);
00123   }
00124 
00125   virtual void getControllerJoints(const std::string &name, std::vector<std::string> &joints)
00126   {
00127     joints = controller_joints_[name];
00128   }
00129 
00130   virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
00131   {
00132     moveit_controller_manager::MoveItControllerManager::ControllerState state;
00133     state.active_ = controllers_[name] & ACTIVE;
00134     state.default_ = false;
00135     return state;
00136   }
00137 
00138 
00139   virtual bool switchControllers(const std::vector<std::string> &activate, const std::vector<std::string> &deactivate)
00140   {
00141     for (std::size_t i = 0 ; i < deactivate.size() ; ++i)
00142     {
00143       controllers_[deactivate[i]] &= ~ACTIVE;
00144       std::cout << "Deactivated controller " << deactivate[i] << std::endl;
00145     }
00146     for (std::size_t i = 0 ; i < activate.size() ; ++i)
00147     {
00148       controllers_[activate[i]] |= ACTIVE;
00149       std::cout << "Activated controller " << activate[i] << std::endl;
00150     }
00151     return true;
00152   }
00153 
00154 protected:
00155 
00156   std::map<std::string, int> controllers_;
00157   std::map<std::string, std::vector<std::string> > controller_joints_;
00158 
00159 };
00160 
00161 
00162 }
00163 #endif


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:31:40