$search
00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2012, PAL Robotics, S.L. 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 PAL Robotics, S.L. 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 00037 // KDL 00038 #include <kdl/chain.hpp> 00039 #include <kdl/tree.hpp> 00040 #include <kdl/treefksolverpos_recursive.hpp> 00041 #include <kdl/treejnttojacsolver.hpp> 00042 00043 // Local 00044 #include <reem_kinematics_constraint_aware/matrix_inverter.h> 00045 #include <reem_kinematics_constraint_aware/ik_solver.h> 00046 #include <ros/ros.h> // TODO: REMOVE! 00047 using namespace reem_kinematics_constraint_aware; 00048 using std::size_t; 00049 using Eigen::VectorXd; 00050 00051 IkSolver::IkSolver(const KDL::Tree& tree, 00052 const EndpointNameList& endpoint_names, 00053 const EndpointCouplingList& endpoint_couplings) 00054 { 00055 init(tree, endpoint_names, endpoint_couplings); 00056 } 00057 00058 IkSolver::IkSolver(const KDL::Chain& chain) 00059 { 00060 const std::string root_name = chain.getSegment(0).getName(); 00061 const std::string tip_name = chain.getSegment(chain.getNrOfSegments() - 1).getName(); 00062 00063 KDL::Tree tree("root"); 00064 tree.addChain(chain, "root"); 00065 00066 std::vector<std::string> endpoint_names(1, tip_name); 00067 std::vector<EndpointCoupling> endpoint_couplings(1, Pose); 00068 00069 init(tree, endpoint_names, endpoint_couplings); 00070 } 00071 00072 IkSolver::~IkSolver() {} 00073 00074 void IkSolver::init(const KDL::Tree& tree, 00075 const std::vector<std::string>& endpoint_names, 00076 const std::vector<EndpointCoupling>& endpoint_couplings) 00077 { 00078 // Preconditions 00079 assert(endpoint_names.size() == endpoint_couplings.size() && "endpoints and coupling vectors size mismatch"); 00080 // TODO: Verify that all endpoints are contained in tree 00081 00082 // Enpoint names vector 00083 endpoint_names_ = endpoint_names; 00084 00085 // Problem size 00086 const size_t q_dim = tree.getNrOfJoints(); // Joint space dimension 00087 size_t x_dim = 0; // Task space dimension, value assigned below 00088 00089 // Populate coupled directions vector 00090 coupled_dirs_.resize(endpoint_names_.size()); 00091 for (size_t i = 0; i < coupled_dirs_.size(); ++i) 00092 { 00093 if ((endpoint_couplings[i] & Position) == Position) 00094 { 00095 coupled_dirs_[i].push_back(0); 00096 coupled_dirs_[i].push_back(1); 00097 coupled_dirs_[i].push_back(2); 00098 x_dim += 3; 00099 } 00100 if ((endpoint_couplings[i] & Orientation) == Orientation) 00101 { 00102 coupled_dirs_[i].push_back(3); 00103 coupled_dirs_[i].push_back(4); 00104 coupled_dirs_[i].push_back(5); 00105 x_dim += 3; 00106 } 00107 } 00108 00109 // Initialize kinematics solvers 00110 fk_solver_.reset(new FkSolver(tree)); 00111 jac_solver_.reset(new JacSolver(tree)); 00112 inverter_.reset(new Inverter(x_dim, q_dim)); 00113 00114 // Matrix inversion parameters TODO: Expose! 00115 inverter_->setLsInverseThreshold(1e-5); // NOTE: Magic values 00116 inverter_->setDlsInverseThreshold(1e-4); 00117 inverter_->setMaxDamping(0.05); 00118 00119 // Default values of position solver parameters 00120 delta_twist_max_ = Eigen::NumTraits<double>::highest(); 00121 delta_joint_pos_max_ = Eigen::NumTraits<double>::highest(); 00122 velik_gain_ = 1.0; 00123 eps_ = Eigen::NumTraits<double>::epsilon(); 00124 max_iter_ = 1; 00125 00126 // Populate map from joint names to KDL tree indices 00127 joint_name_to_idx_.clear(); 00128 const KDL::SegmentMap& tree_segments = tree.getSegments(); 00129 for (KDL::SegmentMap::const_iterator it = tree_segments.begin(); it != tree_segments.end(); ++it) 00130 { 00131 const KDL::Joint& joint = it->second.segment.getJoint(); 00132 if (joint.getType() != KDL::Joint::None) 00133 { 00134 joint_name_to_idx_[joint.getName()] = it->second.q_nr; 00135 } 00136 } 00137 00138 // Joint space weights updater 00139 limits_avoider_.reset(new JointPositionLimitsAvoider(q_dim)); 00140 limits_avoider_->setSmoothing(0.8); // NOTE: Magic value 00141 00142 // Preallocate IK resources 00143 delta_twist_ = VectorXd::Zero(x_dim); 00144 delta_q_ = VectorXd::Zero(q_dim); 00145 q_tmp_ = VectorXd::Zero(q_dim); 00146 00147 jacobian_ = Eigen::MatrixXd(x_dim, q_dim); 00148 jacobian_tmp_ = KDL::Jacobian(q_dim); 00149 00150 Wx_ = VectorXd::Ones(x_dim); 00151 00152 q_posture_ = KDL::JntArray(q_dim); 00153 nullspace_projector_ = Eigen::MatrixXd(q_dim, q_dim); 00154 identity_qdim_ = Eigen::MatrixXd::Identity(q_dim, q_dim); 00155 } 00156 00157 bool IkSolver::solve(const KDL::JntArray& q_current, 00158 const std::vector<KDL::Frame>& x_desired, 00159 KDL::JntArray& q_next) 00160 { 00161 // Precondition 00162 assert(endpoint_names_.size() == x_desired.size()); 00163 00164 q_next = q_current; 00165 q_tmp_ = q_current.data; 00166 00167 // Update joint-space weight matrix: Limit effect of joints near their position limit 00168 limits_avoider_->resetJointLimitAvoidance().applyJointLimitAvoidance(q_next.data); 00169 00170 size_t i; 00171 double delta_twist_norm; 00172 for (i = 0; i < max_iter_; ++i) 00173 { 00174 // Update current task space velocity error 00175 updateDeltaTwist(q_next, x_desired); 00176 delta_twist_norm = delta_twist_.dot(Wx_.asDiagonal() * delta_twist_); // Weighted norm 00177 if (delta_twist_norm < eps_) {break;} 00178 00179 // Enforce task space maximum velocity through uniform scaling 00180 const double delta_twist_scaling = delta_twist_max_ / delta_twist_.cwiseAbs().maxCoeff(); 00181 if (delta_twist_scaling < 1.0) {delta_twist_ *= delta_twist_scaling;} 00182 00183 // Update Jacobian 00184 updateJacobian(q_next); 00185 00186 // Velocity IK: Compute incremental joint displacement and scale according to gain 00187 00188 // Prepare computation of IK with nullspace optimization 00189 using Eigen::MatrixXd; 00190 using Eigen::VectorXd; 00191 using Eigen::DiagonalWrapper; 00192 00193 const MatrixXd& J = jacobian_; // Convenience alias 00194 const DiagonalWrapper<const VectorXd> Wq = limits_avoider_->getWeights().asDiagonal(); // Convenience alias 00195 const DiagonalWrapper<const VectorXd> Wx = Wx_.asDiagonal(); // Convenience alias 00196 00197 // Perform SVD decomposition of J W 00198 inverter_->compute(Wx * J * Wq); 00199 00200 // Nullspace projector 00201 nullspace_projector_ = identity_qdim_ - Wq * inverter_->inverse() * Wx * J; // NOTE: Not rt-friendly, allocates temporaries 00202 00203 // Compute incremental joint displacement 00204 delta_q_ = Wq * inverter_->dlsSolve(Wx * delta_twist_) + nullspace_projector_ * (q_posture_.data - q_next.data); 00205 delta_q_ *= velik_gain_; 00206 00207 // Enforce joint space maximum velocity through uniform scaling 00208 const double delta_q_scaling = delta_joint_pos_max_ / delta_q_.cwiseAbs().maxCoeff(); 00209 if (delta_q_scaling < 1.0) {delta_q_ *= delta_q_scaling;} 00210 00211 // Cache value of q_next 00212 q_tmp_ = q_next.data; 00213 00214 // Integrate joint velocity 00215 q_next.data += delta_q_; 00216 00217 // Enforce joint position limits 00218 00219 // Update joint-space weight matrix: Limit effect of joints near their position limit 00220 limits_avoider_->applyJointLimitAvoidance(q_next.data); 00221 00222 if (!limits_avoider_->isValid(q_next.data)) 00223 { 00224 // Keep last configuration that does not exceed position limits 00225 q_next.data = q_tmp_; 00226 // ROS_DEBUG_STREAM("Iteration " << i << ", not updating joint position values, weights = " << limits_avoider_->getWeights().transpose()); 00227 } 00228 00229 // ROS_DEBUG_STREAM("Iteration " << i << ", delta_twist_norm " << delta_twist_.norm() << ", delta_q_scaling " << delta_q_scaling << ", q_next " << q_next.data.transpose()); // TODO: Remove? 00230 } 00231 00232 updateDeltaTwist(q_next, x_desired); delta_twist_norm = delta_twist_.transpose().dot(Wx_.asDiagonal() * delta_twist_); // Only needed by below debug message 00233 ROS_DEBUG_STREAM("Total iterations " << i << ", delta_twist_norm " << delta_twist_norm << " (eps " << eps_ << "), q " << q_next.data.transpose()); 00234 00235 return (i < max_iter_); 00236 } 00237 00238 void IkSolver::updateDeltaTwist(const KDL::JntArray& q, const std::vector<KDL::Frame>& x_desired) 00239 { 00240 KDL::Frame ith_frame; 00241 KDL::Twist ith_delta_twist; 00242 size_t x_idx = 0; 00243 for (size_t i = 0; i < endpoint_names_.size(); ++i) 00244 { 00245 // Forward kinematics of ith endpoint 00246 fk_solver_->JntToCart(q, ith_frame, endpoint_names_[i]); 00247 ith_delta_twist = diff(ith_frame, x_desired[i]); 00248 00249 KDL::Vector rot = ith_frame.M.GetRot(); 00250 KDL::Vector rot_d = x_desired[i].M.GetRot(); 00251 00252 // Extract only task-space directions relevant to the IK problem 00253 const CoupledDirections& endpoint_coupled_dirs = coupled_dirs_[i]; 00254 for (size_t j = 0; j < endpoint_coupled_dirs.size(); ++j) 00255 { 00256 delta_twist_(x_idx) = ith_delta_twist[endpoint_coupled_dirs[j]]; 00257 ++x_idx; 00258 } 00259 } 00260 } 00261 00262 void IkSolver::updateJacobian(const KDL::JntArray& q) 00263 { 00264 size_t x_idx = 0; 00265 00266 for (size_t i = 0; i < endpoint_names_.size(); ++i) 00267 { 00268 // Jacobian of ith endpoint 00269 jac_solver_->JntToJac(q, jacobian_tmp_, endpoint_names_[i]); 00270 00271 // Extract only task-space directions (Jacobian rows) relevant to the IK problem 00272 const CoupledDirections& endpoint_coupled_dirs = coupled_dirs_[i]; 00273 for (size_t j = 0; j < endpoint_coupled_dirs.size(); ++j) 00274 { 00275 jacobian_.row(x_idx) = jacobian_tmp_.data.row(endpoint_coupled_dirs[j]); 00276 ++x_idx; 00277 } 00278 } 00279 } 00280 00281 JointPositionLimitsAvoider& JointPositionLimitsAvoider::setJointLimits(const Eigen::VectorXd& q_min, 00282 const Eigen::VectorXd& q_max, 00283 double activation_window) 00284 { 00285 assert(w_.size() == q_min.size() && "qmin size mismatch."); 00286 assert(w_.size() == q_max.size() && "qmax size mismatch."); 00287 assert(activation_window >= 0.0 && activation_window <= 1.0 && "Activation window should belong to [0, 1]."); 00288 00289 q_min_ = q_min; 00290 q_max_ = q_max; 00291 q_activation_size_ = (q_max_ - q_min_).cwiseAbs() * activation_window; 00292 q_activation_min_ = q_min_ + q_activation_size_; 00293 q_activation_max_ = q_max_ - q_activation_size_; 00294 return *this; 00295 } 00296 00297 JointPositionLimitsAvoider& JointPositionLimitsAvoider::applyJointLimitAvoidance(const Eigen::VectorXd& q) 00298 { 00299 assert(q.size() == w_.size()); 00300 00301 typedef Eigen::VectorXd::Index Index; 00302 for (Index i = 0; i < q.size(); ++i) 00303 { 00304 if (q(i) <= q_min_(i)) 00305 { 00306 // Minimum joint position limit violated 00307 w_scaling_(i) = 0.0; 00308 } 00309 else if (q(i) >= q_max_(i)) 00310 { 00311 // Maximum joint position limit violated 00312 w_scaling_(i) = 0.0; 00313 } 00314 else if (q(i) < q_activation_min_(i)) 00315 { 00316 // In the lower joint limit avoidance zone. 00317 const double activation = std::abs(q(i) - q_activation_min_(i)) / q_activation_size_(i); // Grows linearly from 0 to 1 as joint limit is apprached 00318 w_scaling_(i) = 1.0 - 1.0 / (1 + std::exp(-12.0 * activation + 6.0 )); // Generalized logistic function mapping [0, 1] to [1, 0] 00319 00320 // If moving away from joint limit, make further progress less difficult. Transition to no scaling is low-pass 00321 // filtered to avoid discontinuities and reduce weight value chattering across IK iterations 00322 if (w_scaling_(i) > w_scaling_prev_(i)) 00323 { 00324 w_scaling_(i) = 1.0 - smoothing_ * (1.0 - w_scaling_(i)); 00325 } 00326 } 00327 else if (q(i) > q_activation_max_(i)) 00328 { 00329 // In the upper joint limit avoidance zone 00330 const double activation = std::abs(q_activation_max_(i) - q(i)) / q_activation_size_(i); // Grows linearly from 0 to 1 as joint limit is apprached 00331 w_scaling_(i) = 1.0 - 1.0 / (1 + std::exp(-12.0 * activation + 6.0 )); // Generalized logistic function mapping [0, 1] to [1, 0] 00332 00333 // If moving away from joint limit, make further progress less difficult. Transition to no scaling is low-pass 00334 // filtered to avoid discontinuities and reduce weight value chattering across IK iterations 00335 if (w_scaling_(i) > w_scaling_prev_(i)) 00336 { 00337 w_scaling_(i) = 1.0 - smoothing_ * (1.0 - w_scaling_(i)); 00338 } 00339 } 00340 else 00341 { 00342 w_scaling_(i) = 1.0; 00343 } 00344 } 00345 00346 // Scale weights 00347 w_scaled_ = w_.cwiseProduct(w_scaling_); 00348 00349 // Update previous value 00350 w_scaling_prev_ = w_scaling_; 00351 00352 // ROS_DEBUG_STREAM(">> Joint space weights diagonal: " << w_scaled_.transpose()); // TODO: Remove! 00353 return *this; 00354 }