hyqleg_inverse_kinematics.cc
Go to the documentation of this file.
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/hyqleg_inverse_kinematics.h>
00031 
00032 #include <cmath>
00033 #include <map>
00034 
00035 #include <xpp_states/cartesian_declarations.h>
00036 
00037 
00038 namespace xpp {
00039 
00040 
00041 HyqlegInverseKinematics::Vector3d
00042 HyqlegInverseKinematics::GetJointAngles (const Vector3d& ee_pos_B, KneeBend bend) const
00043 {
00044   double q_HAA_bf, q_HAA_br, q_HFE_br; // rear bend of knees
00045   double q_HFE_bf, q_KFE_br, q_KFE_bf; // forward bend of knees
00046 
00047   Eigen::Vector3d xr;
00048   Eigen::Matrix3d R;
00049 
00050   // translate to the local coordinate of the attachment of the leg
00051   // and flip coordinate signs such that all computations can be done
00052   // for the front-left leg
00053   xr = ee_pos_B;
00054 
00055   // compute the HAA angle
00056   q_HAA_bf = q_HAA_br = -atan2(xr[Y],-xr[Z]);
00057 
00058   // rotate into the HFE coordinate system (rot around X)
00059   R << 1.0, 0.0, 0.0, 0.0, cos(q_HAA_bf), -sin(q_HAA_bf), 0.0, sin(q_HAA_bf), cos(q_HAA_bf);
00060 
00061   xr = (R * xr).eval();
00062 
00063   // translate into the HFE coordinate system (along Z axis)
00064   xr += hfe_to_haa_z;  //distance of HFE to HAA in z direction
00065 
00066   // compute square of length from HFE to foot
00067   double tmp1 = pow(xr[X],2)+pow(xr[Z],2);
00068 
00069 
00070   // compute temporary angles (with reachability check)
00071   double lu = length_thigh;  // length of upper leg
00072   double ll = length_shank;  // length of lower leg
00073   double alpha = atan2(-xr[Z],xr[X]) - 0.5*M_PI;  //  flip and rotate to match HyQ joint definition
00074 
00075 
00076   double some_random_value_for_beta = (pow(lu,2)+tmp1-pow(ll,2))/(2.*lu*sqrt(tmp1)); // this must be between -1 and 1
00077   if (some_random_value_for_beta > 1) {
00078     some_random_value_for_beta = 1;
00079   }
00080   if (some_random_value_for_beta < -1) {
00081     some_random_value_for_beta = -1;
00082   }
00083   double beta = acos(some_random_value_for_beta);
00084 
00085   // compute Hip FE angle
00086   q_HFE_bf = q_HFE_br = alpha + beta;
00087 
00088 
00089   double some_random_value_for_gamma = (pow(ll,2)+pow(lu,2)-tmp1)/(2.*ll*lu);
00090   // law of cosines give the knee angle
00091   if (some_random_value_for_gamma > 1) {
00092     some_random_value_for_gamma = 1;
00093   }
00094   if (some_random_value_for_gamma < -1) {
00095     some_random_value_for_gamma = -1;
00096   }
00097   double gamma  = acos(some_random_value_for_gamma);
00098 
00099 
00100   q_KFE_bf = q_KFE_br = gamma - M_PI;
00101 
00102   // forward knee bend
00103   EnforceLimits(q_HAA_bf, HAA);
00104   EnforceLimits(q_HFE_bf, HFE);
00105   EnforceLimits(q_KFE_bf, KFE);
00106 
00107   // backward knee bend
00108   EnforceLimits(q_HAA_br, HAA);
00109   EnforceLimits(q_HFE_br, HFE);
00110   EnforceLimits(q_KFE_br, KFE);
00111 
00112   if (bend==Forward)
00113     return Vector3d(q_HAA_bf, q_HFE_bf, q_KFE_bf);
00114   else // backward
00115     return Vector3d(q_HAA_br, -q_HFE_br, -q_KFE_br);
00116 }
00117 
00118 void
00119 HyqlegInverseKinematics::EnforceLimits (double& val, HyqJointID joint) const
00120 {
00121   // totally exaggerated joint angle limits
00122   const static double haa_min = -180;
00123   const static double haa_max =  90;
00124 
00125   const static double hfe_min = -90;
00126   const static double hfe_max =  90;
00127 
00128   const static double kfe_min = -180;
00129   const static double kfe_max =  0;
00130 
00131   // reduced joint angles for optimization
00132   static const std::map<HyqJointID, double> max_range {
00133     {HAA, haa_max/180.0*M_PI},
00134     {HFE, hfe_max/180.0*M_PI},
00135     {KFE, kfe_max/180.0*M_PI}
00136   };
00137 
00138   // reduced joint angles for optimization
00139   static const std::map<HyqJointID, double> min_range {
00140     {HAA, haa_min/180.0*M_PI},
00141     {HFE, hfe_min/180.0*M_PI},
00142     {KFE, kfe_min/180.0*M_PI}
00143   };
00144 
00145   double max = max_range.at(joint);
00146   val = val>max? max : val;
00147 
00148   double min = min_range.at(joint);
00149   val = val<min? min : val;
00150 }
00151 
00152 } /* namespace xpp */


xpp_hyq
Author(s): Alexander W. Winkler, Diego Pardo. , Carlos Mastalli , Ioannis Havoutis
autogenerated on Fri Apr 5 2019 02:55:54