00001 /****************************************************************************** 00002 Copyright (c) 2017, Alexander W. Winkler. All rights reserved. 00003 00004 Redistribution and use in source and binary forms, with or without 00005 modification, are permitted provided that the following conditions are met: 00006 00007 * Redistributions of source code must retain the above copyright notice, this 00008 list of conditions and the following disclaimer. 00009 00010 * Redistributions in binary form must reproduce the above copyright notice, 00011 this list of conditions and the following disclaimer in the documentation 00012 and/or other materials provided with the distribution. 00013 00014 * Neither the name of the copyright holder nor the names of its 00015 contributors may be used to endorse or promote products derived from 00016 this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00028 ******************************************************************************/ 00029 00030 #include <xpp_hyq/inverse_kinematics_hyq4.h> 00031 00032 #include <xpp_states/cartesian_declarations.h> 00033 #include <xpp_states/endeffector_mappings.h> 00034 00035 namespace xpp { 00036 00037 Joints 00038 InverseKinematicsHyq4::GetAllJointAngles(const EndeffectorsPos& x_B) const 00039 { 00040 Vector3d ee_pos_H; // foothold expressed in hip frame 00041 std::vector<Eigen::VectorXd> q_vec; 00042 00043 // make sure always exactly 4 elements 00044 auto pos_B = x_B.ToImpl(); 00045 pos_B.resize(4, pos_B.front()); 00046 00047 for (int ee=0; ee<pos_B.size(); ++ee) { 00048 00049 HyqlegInverseKinematics::KneeBend bend = HyqlegInverseKinematics::Forward; 00050 00051 using namespace quad; 00052 switch (ee) { 00053 case LF: 00054 ee_pos_H = pos_B.at(ee); 00055 break; 00056 case RF: 00057 ee_pos_H = pos_B.at(ee).cwiseProduct(Eigen::Vector3d(1,-1,1)); 00058 break; 00059 case LH: 00060 ee_pos_H = pos_B.at(ee).cwiseProduct(Eigen::Vector3d(-1,1,1)); 00061 bend = HyqlegInverseKinematics::Backward; 00062 break; 00063 case RH: 00064 ee_pos_H = pos_B.at(ee).cwiseProduct(Eigen::Vector3d(-1,-1,1)); 00065 bend = HyqlegInverseKinematics::Backward; 00066 break; 00067 default: // joint angles for this foot do not exist 00068 break; 00069 } 00070 00071 ee_pos_H -= base2hip_LF_; 00072 q_vec.push_back(leg.GetJointAngles(ee_pos_H, bend)); 00073 } 00074 00075 return Joints(q_vec); 00076 } 00077 00078 } /* namespace xpp */