cartesian_wrench.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *  Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, Fetch Robotics Inc.
00005  *  Copyright (c) 2013, Unbounded Robotics Inc.
00006  *  Copyright (c) 2008, Willow Garage, Inc.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Unbounded Robotics nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *********************************************************************/
00036 
00037 /*
00038  * Derived a bit from pr2_controllers/cartesian_wrench_controller.cpp
00039  * Author: Michael Ferguson, Wim Meeussen
00040  */
00041 
00042 #include <pluginlib/class_list_macros.h>
00043 #include <robot_controllers/cartesian_wrench.h>
00044 
00045 #include <urdf/model.h>
00046 #include <kdl_parser/kdl_parser.hpp>
00047 
00048 PLUGINLIB_EXPORT_CLASS(robot_controllers::CartesianWrenchController, robot_controllers::Controller)
00049 
00050 namespace robot_controllers
00051 {
00052 
00053 CartesianWrenchController::CartesianWrenchController() :
00054     initialized_(false)
00055 {
00056 }
00057 
00058 int CartesianWrenchController::init(ros::NodeHandle& nh, ControllerManager* manager)
00059 {
00060   // We absolutely need access to the controller manager
00061   if (!manager)
00062   {
00063     initialized_ = false;
00064     return -1;
00065   }
00066 
00067   Controller::init(nh, manager);
00068   manager_ = manager;
00069 
00070   // Initialize KDL structures
00071   std::string tip_link;
00072   nh.param<std::string>("root_name", root_link_, "torso_lift_link");
00073   nh.param<std::string>("tip_name", tip_link, "gripper_link");
00074 
00075   // Load URDF
00076   urdf::Model model;
00077   if (!model.initParam("robot_description"))
00078   {
00079     ROS_ERROR("Failed to parse URDF");
00080     return -1;
00081   }
00082 
00083   // Load the tree
00084   KDL::Tree kdl_tree;
00085   if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
00086   {
00087     ROS_ERROR("Could not construct tree from URDF");
00088     return -1;
00089   }
00090 
00091   // Populate the chain
00092   if(!kdl_tree.getChain(root_link_, tip_link, kdl_chain_))
00093   {
00094     ROS_ERROR("Could not construct chain from URDF");
00095     return -1;
00096   }
00097 
00098   jac_solver_.reset(new KDL::ChainJntToJacSolver(kdl_chain_));
00099   jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00100   jnt_eff_.resize(kdl_chain_.getNrOfJoints());
00101   jacobian_.resize(kdl_chain_.getNrOfJoints());
00102 
00103   // Init joint handles
00104   joints_.clear();
00105   for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00106     if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00107       joints_.push_back(manager_->getJointHandle(kdl_chain_.getSegment(i).getJoint().getName()));
00108 
00109   // Subscribe to command
00110   command_sub_ = nh.subscribe<geometry_msgs::Wrench>("command", 1,
00111                     boost::bind(&CartesianWrenchController::command, this, _1));
00112   last_command_ = ros::Time(0);
00113 
00114   initialized_ = true;
00115   return 0;
00116 }
00117 
00118 bool CartesianWrenchController::start()
00119 {
00120   if (!initialized_)
00121   {
00122     ROS_ERROR_NAMED("CartesianWrenchController",
00123                     "Unable to start, not initialized.");
00124     return false;
00125   }
00126 
00127   if (ros::Time::now() - last_command_ > ros::Duration(3.0))
00128   {
00129     ROS_ERROR_NAMED("CartesianWrenchController",
00130                     "Unable to start, no goal.");
00131     return false;
00132   }
00133 
00134   return true;
00135 }
00136 
00137 bool CartesianWrenchController::stop(bool force)
00138 {
00139   return true;
00140 }
00141 
00142 bool CartesianWrenchController::reset()
00143 {
00144   // Simply stop
00145   return (manager_->requestStop(getName()) == 0);
00146 }
00147 
00148 void CartesianWrenchController::update(const ros::Time& now, const ros::Duration& dt)
00149 {
00150   // Need to initialize KDL structs
00151   if (!initialized_)
00152     return;
00153 
00154   if (ros::Time::now() - last_command_ > ros::Duration(0.1))
00155   {
00156     // Command has timed out, shutdown
00157     manager_->requestStop(getName());
00158     return;
00159   } 
00160 
00161   // This updates jnt_pos_
00162   updateJoints();
00163 
00164   // Get jacobian
00165   jac_solver_->JntToJac(jnt_pos_, jacobian_);
00166 
00167   // Convert wrench to joint efforts
00168   for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
00169   {
00170     jnt_eff_(i) = 0;
00171     for (unsigned int j = 0; j < 6; ++j)
00172       jnt_eff_(i) += (jacobian_(j,i) * desired_wrench_(j));
00173   }
00174 
00175   // Actually update joints
00176   for (size_t j = 0; j < joints_.size(); ++j)
00177     joints_[j]->setEffort(jnt_eff_(j));
00178 }
00179 
00180 void CartesianWrenchController::updateJoints()
00181 {
00182   for (size_t i = 0; i < joints_.size(); ++i)
00183     jnt_pos_(i) = joints_[i]->getPosition();
00184 }
00185 
00186 void CartesianWrenchController::command(const geometry_msgs::Wrench::ConstPtr& goal)
00187 {
00188   // Update command
00189   desired_wrench_.force(0) = goal->force.x;
00190   desired_wrench_.force(1) = goal->force.y;
00191   desired_wrench_.force(2) = goal->force.z;
00192   desired_wrench_.torque(0) = goal->torque.x;
00193   desired_wrench_.torque(1) = goal->torque.y;
00194   desired_wrench_.torque(2) = goal->torque.z;
00195 
00196   // Update last command time before trying to start controller
00197   last_command_ = ros::Time::now();
00198 
00199   // Try to start up
00200   if (manager_->requestStart(getName()) != 0)
00201   {
00202     ROS_ERROR("CartesianWrenchController: Cannot start, blocked by another controller.");
00203     return;
00204   }
00205 }
00206 
00207 std::vector<std::string> CartesianWrenchController::getCommandedNames()
00208 {
00209   std::vector<std::string> names;
00210   if (initialized_)
00211   {
00212     for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00213       if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00214         names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
00215   }
00216   return names;
00217 }
00218 
00219 std::vector<std::string> CartesianWrenchController::getClaimedNames()
00220 {
00221   return getCommandedNames();
00222 }
00223 
00224 }  // namespace robot_controllers


robot_controllers
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:10