00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2016, CRI group, NTU, Singapore 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 CRI group 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 00035 /* Author: Francisco Suarez-Ruiz */ 00036 00037 #ifndef KDLCHAINIKSOLVERPOS_LMA_JL_MIMIC_H 00038 #define KDLCHAINIKSOLVERPOS_LMA_JL_MIMIC_H 00039 00040 #include "kdl/chainiksolverpos_lma.hpp" // Solver for the inverse position kinematics that uses Levenberg-Marquardt. 00041 #include "kdl/chainfksolver.hpp" 00042 00043 #include <moveit/lma_kinematics_plugin/joint_mimic.h> 00044 00045 namespace KDL 00046 { 00055 class ChainIkSolverPos_LMA_JL_Mimic : public ChainIkSolverPos 00056 { 00057 public: 00075 ChainIkSolverPos_LMA_JL_Mimic(const Chain& chain, const JntArray& q_min, const JntArray& q_max, 00076 ChainFkSolverPos& fksolver, ChainIkSolverPos_LMA& iksolver, unsigned int maxiter = 100, 00077 double eps = 1e-6, bool position_ik = false); 00078 00079 ~ChainIkSolverPos_LMA_JL_Mimic(); 00080 00081 virtual int CartToJnt(const JntArray& q_init, const Frame& p_in, JntArray& q_out); 00082 00083 virtual int CartToJntAdvanced(const JntArray& q_init, const Frame& p_in, JntArray& q_out, bool lock_redundant_joints); 00084 00085 bool setMimicJoints(const std::vector<lma_kinematics_plugin::JointMimic>& mimic_joints); 00086 00087 private: 00088 const Chain chain; 00089 JntArray q_min; // These are the limits for the "reduced" state consisting of only active DOFs 00090 JntArray q_min_mimic; // These are the limits for the full state 00091 JntArray q_max; // These are the limits for the "reduced" state consisting of only active DOFs 00092 JntArray q_max_mimic; // These are the limits for the full state 00093 JntArray q_temp; 00094 ChainFkSolverPos& fksolver; 00095 ChainIkSolverPos_LMA& iksolver; 00096 JntArray delta_q; 00097 Frame f; 00098 Twist delta_twist; 00099 unsigned int maxiter; 00100 double eps; 00101 std::vector<lma_kinematics_plugin::JointMimic> mimic_joints; 00102 void qToqMimic(const JntArray& q, 00103 JntArray& q_result); // Convert from the "reduced" state (only active DOFs) to the "full" state 00104 void qMimicToq(const JntArray& q, JntArray& q_result); // Convert from the "full" state to the "reduced" state 00105 void harmonize(JntArray& q_out); // Puts the angles within [-2PI, 2PI] 00106 bool obeysLimits(const KDL::JntArray& q_out); // Checks that a set of joint angles obey the urdf limits 00107 bool position_ik; 00108 }; 00109 } 00110 00111 #endif