cartesian_pose.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_pose_controller.cpp
00039  * Author: Michael Ferguson, Wim Meeussen
00040  */
00041 
00042 #include <pluginlib/class_list_macros.h>
00043 #include <robot_controllers/cartesian_pose.h>
00044 
00045 #include <urdf/model.h>
00046 #include <kdl_parser/kdl_parser.hpp>
00047 
00048 #include <tf_conversions/tf_kdl.h>
00049 
00050 PLUGINLIB_EXPORT_CLASS(robot_controllers::CartesianPoseController, robot_controllers::Controller)
00051 
00052 namespace robot_controllers
00053 {
00054 
00055 CartesianPoseController::CartesianPoseController() :
00056     initialized_(false)
00057 {
00058 }
00059 
00060 int CartesianPoseController::init(ros::NodeHandle& nh, ControllerManager* manager)
00061 {
00062   // We absolutely need access to the controller manager
00063   if (!manager)
00064   {
00065     initialized_ = false;
00066     return -1;
00067   }
00068 
00069   Controller::init(nh, manager);
00070   manager_ = manager;
00071 
00072   // Initialize KDL structures
00073   std::string tip_link;
00074   nh.param<std::string>("root_name", root_link_, "torso_lift_link");
00075   nh.param<std::string>("tip_name", tip_link, "gripper_link");
00076 
00077   // Load URDF
00078   urdf::Model model;
00079   if (!model.initParam("robot_description"))
00080   {
00081     ROS_ERROR("Failed to parse URDF");
00082     return -1;
00083   }
00084 
00085   // Load the tree
00086   KDL::Tree kdl_tree;
00087   if (!kdl_parser::treeFromUrdfModel(model, kdl_tree))
00088   {
00089     ROS_ERROR("Could not construct tree from URDF");
00090     return -1;
00091   }
00092 
00093   // Populate the chain
00094   if(!kdl_tree.getChain(root_link_, tip_link, kdl_chain_))
00095   {
00096     ROS_ERROR("Could not construct chain from URDF");
00097     return -1;
00098   }
00099 
00100   jnt_to_pose_solver_.reset(new KDL::ChainFkSolverPos_recursive(kdl_chain_));
00101   jac_solver_.reset(new KDL::ChainJntToJacSolver(kdl_chain_));
00102   jnt_pos_.resize(kdl_chain_.getNrOfJoints());
00103   jnt_delta_.resize(kdl_chain_.getNrOfJoints());
00104   jacobian_.resize(kdl_chain_.getNrOfJoints());
00105 
00106   // Initialize controllers
00107   robot_controllers::PID pid_controller;
00108   if (!pid_controller.init(ros::NodeHandle(nh,"fb_trans"))) return false;
00109   for (unsigned int i = 0; i < 3; i++)
00110     pid_.push_back(pid_controller);
00111   if (!pid_controller.init(ros::NodeHandle(nh,"fb_rot"))) return false;
00112   for (unsigned int i = 0; i < 3; i++)
00113     pid_.push_back(pid_controller);
00114 
00115   // Init joint handles
00116   joints_.clear();
00117   for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00118     if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00119       joints_.push_back(manager_->getJointHandle(kdl_chain_.getSegment(i).getJoint().getName()));
00120 
00121   // Subscribe to command
00122   command_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("command", 1,
00123                     boost::bind(&CartesianPoseController::command, this, _1));
00124   last_command_ = ros::Time(0);
00125 
00126   // Feedback of twist
00127   feedback_pub_ = nh.advertise<geometry_msgs::Twist>("feedback", 10);
00128 
00129   initialized_ = true;
00130   return 0;
00131 }
00132 
00133 bool CartesianPoseController::start()
00134 {
00135   if (!initialized_)
00136   {
00137     ROS_ERROR_NAMED("CartesianPoseController",
00138                     "Unable to start, not initialized.");
00139     return false;
00140   }
00141 
00142   if (ros::Time::now() - last_command_ > ros::Duration(3.0))
00143   {
00144     ROS_ERROR_NAMED("CartesianPoseController",
00145                     "Unable to start, no goal.");
00146     return false;
00147   }
00148 
00149   return true;
00150 }
00151 
00152 bool CartesianPoseController::stop(bool force)
00153 {
00154   // Always stop
00155   return true;
00156 }
00157 
00158 bool CartesianPoseController::reset()
00159 {
00160   // Simply stop
00161   return (manager_->requestStop(getName()) == 0);
00162 }
00163 
00164 void CartesianPoseController::update(const ros::Time& now, const ros::Duration& dt)
00165 {
00166   // Need to initialize KDL structs
00167   if (!initialized_)
00168     return;  // Should never actually hit this
00169 
00170   // Get current pose
00171   actual_pose_ = getPose();
00172 
00173   // Pose feedback
00174   twist_error_ = KDL::diff(actual_pose_, desired_pose_);
00175   geometry_msgs::Twist t;
00176   t.linear.x = twist_error_(0);
00177   t.linear.y = twist_error_(1);
00178   t.linear.z = twist_error_(2);
00179   t.angular.x = twist_error_(3);
00180   t.angular.y = twist_error_(4);
00181   t.angular.z = twist_error_(5);
00182   feedback_pub_.publish(t);
00183 
00184   // Update PID
00185   for (size_t i = 0; i < 6; ++i)
00186     twist_error_(i) = pid_[i].update(twist_error_(i), dt.toSec());
00187 
00188   // Get jacobian
00189   jac_solver_->JntToJac(jnt_pos_, jacobian_);
00190 
00191   // Convert wrench to joint efforts
00192   for (size_t i = 0; i < kdl_chain_.getNrOfJoints(); ++i)
00193   {
00194     jnt_delta_(i) = 0.0;
00195     for (unsigned int j = 0; j < 6; ++j)
00196       jnt_delta_(i) += (jacobian_(j,i) * twist_error_(j));
00197   }
00198 
00199   // Actually update joints
00200   for (size_t j = 0; j < joints_.size(); ++j)
00201     joints_[j]->setPosition(jnt_delta_(j) + joints_[j]->getPosition(), 0.0, 0.0);
00202 }
00203 
00204 KDL::Frame CartesianPoseController::getPose()
00205 {
00206   for (size_t i = 0; i < joints_.size(); ++i)
00207     jnt_pos_(i) = joints_[i]->getPosition();
00208 
00209   KDL::Frame result;
00210   jnt_to_pose_solver_->JntToCart(jnt_pos_, result);
00211 
00212   return result;
00213 }
00214 
00215 void CartesianPoseController::command(const geometry_msgs::PoseStamped::ConstPtr& goal)
00216 {
00217   // Need to initialize KDL structs
00218   if (!initialized_)
00219   {
00220     ROS_ERROR("CartesianPoseController: Cannot accept goal, controller is not initialized.");
00221     return;
00222   }
00223 
00224   // Need transform
00225   if (!tf_.waitForTransform(goal->header.frame_id, root_link_,
00226                             goal->header.stamp, ros::Duration(0.1)))
00227   {
00228     ROS_ERROR_STREAM("CartesianPoseController: Unable to transform goal to " << root_link_ << ".");
00229     return;
00230   }
00231 
00232   // Update last command time before trying to start controller
00233   last_command_ = ros::Time::now();
00234 
00235   // Try to start up
00236   if (manager_->requestStart(getName()) != 0)
00237   {
00238     ROS_ERROR("CartesianPoseController: Cannot start, blocked by another controller.");
00239     return;
00240   }
00241 
00242   tf::Stamped<tf::Pose> stamped;
00243   tf::poseStampedMsgToTF(*goal, stamped);
00244 
00245   tf_.transformPose(root_link_, stamped, stamped);
00246   tf::poseTFToKDL(stamped, desired_pose_);
00247 }
00248 
00249 std::vector<std::string> CartesianPoseController::getCommandedNames()
00250 {
00251   std::vector<std::string> names;
00252   if (initialized_)
00253   {
00254     for (size_t i = 0; i < kdl_chain_.getNrOfSegments(); ++i)
00255       if (kdl_chain_.getSegment(i).getJoint().getType() != KDL::Joint::None)
00256         names.push_back(kdl_chain_.getSegment(i).getJoint().getName());
00257   }
00258   return names;
00259 }
00260 
00261 std::vector<std::string> CartesianPoseController::getClaimedNames()
00262 {
00263   // Commanded == claimed
00264   return getCommandedNames();
00265 }
00266 
00267 
00268 }  // namespace robot_controllers


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