$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 #ifndef REEM_KINEMATICS_IK_SOLVER_ 00038 #define REEM_KINEMATICS_IK_SOLVER_ 00039 00040 // C++ standard 00041 #include <cassert> 00042 #include <cstddef> 00043 #include <map> 00044 #include <string> 00045 #include <vector> 00046 00047 // Boost 00048 #include <boost/scoped_ptr.hpp> 00049 00050 // Eigen 00051 #include <Eigen/Dense> 00052 00053 // KDL 00054 #include <kdl/jacobian.hpp> 00055 #include <kdl/jntarray.hpp> 00056 00057 namespace KDL 00058 { 00059 template <typename T> class MatrixInverter; 00060 class TreeFkSolverPos_recursive; 00061 class TreeJntToJacSolver; 00062 } 00063 00064 namespace reem_kinematics_constraint_aware 00065 { 00066 00072 class JointPositionLimitsAvoider 00073 { 00074 public: 00076 JointPositionLimitsAvoider(int q_dim) 00077 : w_(Eigen::VectorXd::Ones(q_dim)), 00078 q_min_(Eigen::VectorXd::Constant(q_dim, Eigen::NumTraits<double>::lowest())), 00079 q_max_(Eigen::VectorXd::Constant(q_dim, Eigen::NumTraits<double>::highest())), 00080 q_activation_min_(q_min_), 00081 q_activation_max_(q_max_), 00082 q_activation_size_(Eigen::VectorXd::Zero(q_dim)), 00083 smoothing_(0.0) 00084 { 00085 resetJointLimitAvoidance(); 00086 } 00087 00092 JointPositionLimitsAvoider& setJointLimits(const Eigen::VectorXd& q_min, 00093 const Eigen::VectorXd& q_max, 00094 double activation_window); 00095 00096 JointPositionLimitsAvoider& setWeights(const Eigen::VectorXd& w) 00097 { 00098 assert(w.size() == w_.size() && "Wrong weight vector size."); 00099 w_ = w; 00100 return *this; 00101 } 00102 00103 Eigen::VectorXd& getWeights() {return w_scaled_;} 00104 const Eigen::VectorXd& getWeights() const {return w_scaled_;} 00105 00106 JointPositionLimitsAvoider& setSmoothing(const double smoothing) 00107 { 00108 assert(smoothing >= 0.0 && smoothing <= 1.0 && "Smoothing should belong to [0, 1]."); 00109 smoothing_ = smoothing; 00110 return *this; 00111 } 00112 00113 JointPositionLimitsAvoider& resetJointLimitAvoidance() 00114 { 00115 w_scaling_.setOnes(w_.size()); 00116 w_scaling_prev_ = w_scaling_; 00117 w_scaled_ = w_; 00118 return *this; 00119 } 00120 00123 JointPositionLimitsAvoider& applyJointLimitAvoidance(const Eigen::VectorXd& q); 00124 00126 bool isValid(const Eigen::VectorXd& q) 00127 { 00128 typedef Eigen::VectorXd::Index Index; 00129 for(Index i = 0; i < q_min_.size(); ++i) 00130 { 00131 if (q(i) < q_min_(i) || q(i) > q_max_(i)) {return false;} 00132 } 00133 return true; 00134 } 00135 00136 private: 00137 Eigen::VectorXd w_; 00138 Eigen::VectorXd w_scaled_; 00139 Eigen::VectorXd w_scaling_; 00140 Eigen::VectorXd w_scaling_prev_; 00141 Eigen::VectorXd q_min_; 00142 Eigen::VectorXd q_max_; 00143 Eigen::VectorXd q_activation_min_; 00144 Eigen::VectorXd q_activation_max_; 00145 Eigen::VectorXd q_activation_size_; 00146 00149 double smoothing_; 00150 }; 00151 00152 // TODO: Make a template on floating point type?. Maybe YAGNI because KDL does not support this, as it's doubles everywhere. 00153 class IkSolver 00154 { 00155 public: 00157 enum EndpointCoupling 00158 { 00159 Position = 1, 00160 Orientation = 2, 00161 Pose = Position | Orientation 00162 }; 00163 00164 typedef std::vector<std::string> EndpointNameList; 00165 typedef std::vector<EndpointCoupling> EndpointCouplingList; 00166 00167 // TODO: Map endpoint names to tree segments! 00168 IkSolver(const KDL::Tree& tree, 00169 const EndpointNameList& endpoint_names, 00170 const EndpointCouplingList& endpoint_couplings); 00171 00173 IkSolver(const KDL::Chain& chain); 00174 00175 virtual ~IkSolver(); 00176 00177 bool solve(const KDL::JntArray& q_current, 00178 const std::vector<KDL::Frame>& x_desired, 00179 KDL::JntArray& q_next); 00180 00183 bool solve(const KDL::JntArray& q_current, 00184 const KDL::Frame& x_desired, 00185 KDL::JntArray& q_next); 00186 00187 // TODO: Add getters 00188 void setJointPositionLimits(const Eigen::VectorXd& q_min, const Eigen::VectorXd& q_max); 00189 void setMaxDeltaPosTask(double delta_twist_max) {delta_twist_max_ = delta_twist_max;} 00190 void setMaxDeltaPosJoint(double delta_joint_pos_max) {delta_joint_pos_max_ = delta_joint_pos_max;} 00191 void setVelocityIkGain(double velik_gain) {velik_gain_ = velik_gain;} 00192 void setEpsilon(double eps) {eps_ = eps;} 00193 void setMaxIterations(std::size_t max_iter) {max_iter_ = max_iter;} 00194 void setPosture(const KDL::JntArray& q_posture) {q_posture_ = q_posture;} 00195 void setJointSpaceWeights(const Eigen::VectorXd& Wq) {assert(limits_avoider_); limits_avoider_->setWeights(Wq);} 00196 void setTaskSpaceWeights(const Eigen::VectorXd& Wq) {Wx_ = Wq;} 00197 00198 private: 00199 typedef std::vector<std::size_t> CoupledDirections; 00200 typedef KDL::TreeFkSolverPos_recursive FkSolver; 00201 typedef boost::scoped_ptr<FkSolver> FkSolverPtr; 00202 typedef KDL::TreeJntToJacSolver JacSolver; 00203 typedef boost::scoped_ptr<JacSolver> JacSolverPtr; 00204 typedef KDL::MatrixInverter<Eigen::MatrixXd> Inverter; 00205 typedef boost::scoped_ptr<Inverter> InverterPtr; 00206 typedef std::map<std::string, int> JointNameToIndexMap; 00207 00208 FkSolverPtr fk_solver_; 00209 JacSolverPtr jac_solver_; 00210 InverterPtr inverter_; 00211 00212 std::vector<std::string> endpoint_names_; 00213 std::vector<CoupledDirections> coupled_dirs_; 00214 JointNameToIndexMap joint_name_to_idx_; 00215 00216 Eigen::VectorXd delta_twist_; 00217 Eigen::VectorXd delta_q_; 00218 Eigen::VectorXd q_tmp_; 00219 00220 Eigen::MatrixXd jacobian_; 00221 KDL::Jacobian jacobian_tmp_; 00222 Eigen::VectorXd Wx_; 00223 00224 // Custom velocity-IK members NOTE: Remove this and substitute with generic implementation 00225 Eigen::MatrixXd nullspace_projector_; 00226 Eigen::MatrixXd identity_qdim_; 00227 KDL::JntArray q_posture_; 00228 00229 // Position IK configuration parameters 00230 double delta_twist_max_; 00231 double delta_joint_pos_max_; 00232 double velik_gain_; 00233 double eps_; 00234 std::size_t max_iter_; 00235 00236 boost::scoped_ptr<JointPositionLimitsAvoider> limits_avoider_; 00237 00238 void init(const KDL::Tree& tree, 00239 const std::vector<std::string>& endpoint_names, 00240 const std::vector<EndpointCoupling>& endpoint_couplings); 00241 00242 void updateDeltaTwist(const KDL::JntArray& q, const std::vector<KDL::Frame>& x_desired); 00243 00244 void updateJacobian(const KDL::JntArray& q); 00245 }; 00246 00247 inline void IkSolver::setJointPositionLimits(const Eigen::VectorXd& q_min, const Eigen::VectorXd& q_max) 00248 { 00249 assert(limits_avoider_); 00250 limits_avoider_->setJointLimits(q_min, q_max, 0.2); // NOTE: Magic value 00251 } 00252 00253 inline bool IkSolver::solve(const KDL::JntArray& q_current, 00254 const KDL::Frame& x_desired, 00255 KDL::JntArray& q_next) 00256 { 00257 return solve(q_current, 00258 std::vector<KDL::Frame>(1, x_desired), 00259 q_next); 00260 } 00261 00262 } // reem_kinematics_constraint_aware 00263 00264 #endif // REEM_KINEMATICS_IK_SOLVER_