00001 00002 // Copyright (C) 2015, PAL Robotics S.L. 00003 // 00004 // Redistribution and use in source and binary forms, with or without 00005 // modification, are permitted provided that the following conditions are met: 00006 // * Redistributions of source code must retain the above copyright notice, 00007 // this list of conditions and the following disclaimer. 00008 // * Redistributions in binary form must reproduce the above copyright 00009 // notice, this list of conditions and the following disclaimer in the 00010 // documentation and/or other materials provided with the distribution. 00011 // * Neither the names of PAL Robotics S.L. nor the names of its 00012 // contributors may be used to endorse or promote products derived from 00013 // this software without specific prior written permission. 00014 // 00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 // POSSIBILITY OF SUCH DAMAGE. 00027 00028 #include <controller_manager_tests/pos_eff_opt_controller.h> 00029 00030 using namespace controller_manager_tests; 00031 00032 bool PosEffOptController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &n) 00033 { 00034 std::vector<std::string> pos_joints; 00035 if (!n.getParam("position_joints", pos_joints)) {return false;} 00036 00037 std::vector<std::string> eff_joints; 00038 if (!n.getParam("effort_joints", eff_joints)) {return false;} 00039 00040 typedef std::vector<std::string>::const_iterator NamesIterator; 00041 typedef hardware_interface::PositionJointInterface PosIface; 00042 typedef hardware_interface::EffortJointInterface EffIface; 00043 00044 // In this controller interfaces are optional, so initRequest did not check interface existence 00045 // The position interface is OPTIONAL 00046 // The effort interface is REQUIRED 00047 PosIface* pos_iface = robot_hw->get<PosIface>(); 00048 EffIface* eff_iface = robot_hw->get<EffIface>(); 00049 00050 // populate command handles (claimed resources) 00051 if (pos_iface) 00052 { 00053 for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++) 00054 { 00055 pos_cmd_.push_back(pos_iface->getHandle(*it)); 00056 } 00057 } 00058 else 00059 { 00060 ROS_WARN("Optional interface not found: 'hardware_interface::PositionJointInterface'"); 00061 } 00062 00063 if (eff_iface) 00064 { 00065 for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++) 00066 { 00067 eff_cmd_.push_back(eff_iface->getHandle(*it)); 00068 } 00069 } 00070 else 00071 { 00072 ROS_ERROR("Required interface not found: 'hardware_interface::EffortJointInterface'"); 00073 return false; 00074 } 00075 00076 return true; 00077 } 00078 00079 void PosEffOptController::starting(const ros::Time& /*time*/) 00080 { 00081 ROS_INFO("Starting PosEffOptController"); 00082 } 00083 00084 void PosEffOptController::update(const ros::Time& /*time*/, const ros::Duration& /*period*/) 00085 {} 00086 00087 void PosEffOptController::stopping(const ros::Time& /*time*/) 00088 { 00089 ROS_INFO("Stopping PosEffOptController"); 00090 } 00091 00092 PLUGINLIB_EXPORT_CLASS(controller_manager_tests::PosEffOptController, controller_interface::ControllerBase)