hyqleg_inverse_kinematics.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
31 
32 #include <cmath>
33 #include <map>
34 
36 
37 
38 namespace xpp {
39 
40 
43 {
44  double q_HAA_bf, q_HAA_br, q_HFE_br; // rear bend of knees
45  double q_HFE_bf, q_KFE_br, q_KFE_bf; // forward bend of knees
46 
47  Eigen::Vector3d xr;
48  Eigen::Matrix3d R;
49 
50  // translate to the local coordinate of the attachment of the leg
51  // and flip coordinate signs such that all computations can be done
52  // for the front-left leg
53  xr = ee_pos_B;
54 
55  // compute the HAA angle
56  q_HAA_bf = q_HAA_br = -atan2(xr[Y],-xr[Z]);
57 
58  // rotate into the HFE coordinate system (rot around X)
59  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);
60 
61  xr = (R * xr).eval();
62 
63  // translate into the HFE coordinate system (along Z axis)
64  xr += hfe_to_haa_z; //distance of HFE to HAA in z direction
65 
66  // compute square of length from HFE to foot
67  double tmp1 = pow(xr[X],2)+pow(xr[Z],2);
68 
69 
70  // compute temporary angles (with reachability check)
71  double lu = length_thigh; // length of upper leg
72  double ll = length_shank; // length of lower leg
73  double alpha = atan2(-xr[Z],xr[X]) - 0.5*M_PI; // flip and rotate to match HyQ joint definition
74 
75 
76  double some_random_value_for_beta = (pow(lu,2)+tmp1-pow(ll,2))/(2.*lu*sqrt(tmp1)); // this must be between -1 and 1
77  if (some_random_value_for_beta > 1) {
78  some_random_value_for_beta = 1;
79  }
80  if (some_random_value_for_beta < -1) {
81  some_random_value_for_beta = -1;
82  }
83  double beta = acos(some_random_value_for_beta);
84 
85  // compute Hip FE angle
86  q_HFE_bf = q_HFE_br = alpha + beta;
87 
88 
89  double some_random_value_for_gamma = (pow(ll,2)+pow(lu,2)-tmp1)/(2.*ll*lu);
90  // law of cosines give the knee angle
91  if (some_random_value_for_gamma > 1) {
92  some_random_value_for_gamma = 1;
93  }
94  if (some_random_value_for_gamma < -1) {
95  some_random_value_for_gamma = -1;
96  }
97  double gamma = acos(some_random_value_for_gamma);
98 
99 
100  q_KFE_bf = q_KFE_br = gamma - M_PI;
101 
102  // forward knee bend
103  EnforceLimits(q_HAA_bf, HAA);
104  EnforceLimits(q_HFE_bf, HFE);
105  EnforceLimits(q_KFE_bf, KFE);
106 
107  // backward knee bend
108  EnforceLimits(q_HAA_br, HAA);
109  EnforceLimits(q_HFE_br, HFE);
110  EnforceLimits(q_KFE_br, KFE);
111 
112  if (bend==Forward)
113  return Vector3d(q_HAA_bf, q_HFE_bf, q_KFE_bf);
114  else // backward
115  return Vector3d(q_HAA_br, -q_HFE_br, -q_KFE_br);
116 }
117 
118 void
120 {
121  // totally exaggerated joint angle limits
122  const static double haa_min = -180;
123  const static double haa_max = 90;
124 
125  const static double hfe_min = -90;
126  const static double hfe_max = 90;
127 
128  const static double kfe_min = -180;
129  const static double kfe_max = 0;
130 
131  // reduced joint angles for optimization
132  static const std::map<HyqJointID, double> max_range {
133  {HAA, haa_max/180.0*M_PI},
134  {HFE, hfe_max/180.0*M_PI},
135  {KFE, kfe_max/180.0*M_PI}
136  };
137 
138  // reduced joint angles for optimization
139  static const std::map<HyqJointID, double> min_range {
140  {HAA, haa_min/180.0*M_PI},
141  {HFE, hfe_min/180.0*M_PI},
142  {KFE, kfe_min/180.0*M_PI}
143  };
144 
145  double max = max_range.at(joint);
146  val = val>max? max : val;
147 
148  double min = min_range.at(joint);
149  val = val<min? min : val;
150 }
151 
152 } /* namespace xpp */
void EnforceLimits(double &q, HyqJointID joint) const
Restricts the joint angles to lie inside the feasible range.
R
Vector3d GetJointAngles(const Vector3d &ee_pos_H, KneeBend bend=Forward) const
Returns the joint angles to reach a Cartesian foot position.
double min(double a, double b)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
double max(double a, double b)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)


xpp_hyq
Author(s): Alexander W. Winkler, Diego Pardo. , Carlos Mastalli , Ioannis Havoutis
autogenerated on Tue Dec 8 2020 03:10:35