Joint.cc
Go to the documentation of this file.
1 /*
2  * Original Copyright (c) 2011-2016 Martin Felis <martin.felis@iwr.uni-heidelberg.de>
3  *
4  *
5  * RDL - Robot Dynamics Library
6  * Modifications Copyright (c) 2017 Jordan Lack <jlack1987@gmail.com>
7  *
8  * Licensed under the zlib license. See LICENSE for more details.
9  */
10 
11 #include <iostream>
12 #include <limits>
13 #include <assert.h>
14 
15 #include "rdl_dynamics/Model.h"
17 
18 namespace RobotDynamics
19 {
20 
21  using namespace Math;
22 
23  void jcalc(Model &model, unsigned int joint_id, const VectorNd &q, const VectorNd &qdot)
24  {
25  // exception if we calculate it for the root body
26  assert (joint_id > 0);
27 
28  if(model.mJoints[joint_id].mJointType == JointTypeRevoluteX)
29  {
30  model.X_J[joint_id] = Xrotx(q[model.mJoints[joint_id].q_index]);
31  model.v_J[joint_id].wx() = qdot[model.mJoints[joint_id].q_index];
32  }
33  else if(model.mJoints[joint_id].mJointType == JointTypeRevoluteY)
34  {
35  model.X_J[joint_id] = Xroty(q[model.mJoints[joint_id].q_index]);
36  model.v_J[joint_id].wy() = qdot[model.mJoints[joint_id].q_index];
37  }
38  else if(model.mJoints[joint_id].mJointType == JointTypeRevoluteZ)
39  {
40  model.X_J[joint_id] = Xrotz(q[model.mJoints[joint_id].q_index]);
41  model.v_J[joint_id].wz() = qdot[model.mJoints[joint_id].q_index];
42  }
43  else if(model.mJoints[joint_id].mDoFCount == 1 && model.mJoints[joint_id].mJointType != JointTypeCustom)
44  {
45  model.X_J[joint_id] = jcalc_XJ(model, joint_id, q);
46 
47  model.v_J[joint_id].set(model.S[joint_id] * qdot[model.mJoints[joint_id].q_index]);
48  }
49  else if(model.mJoints[joint_id].mJointType == JointTypeSpherical)
50  {
51  model.X_J[joint_id] = SpatialTransform(Math::toMatrix(model.GetQuaternion(joint_id, q)), Vector3d(0., 0., 0.));
52 
53  model.multdof3_S[joint_id](0, 0) = 1.;
54  model.multdof3_S[joint_id](1, 1) = 1.;
55  model.multdof3_S[joint_id](2, 2) = 1.;
56 
57  Vector3d omega(qdot[model.mJoints[joint_id].q_index], qdot[model.mJoints[joint_id].q_index + 1], qdot[model.mJoints[joint_id].q_index + 2]);
58 
59  model.v_J[joint_id].set(SpatialVector(omega[0], omega[1], omega[2], 0., 0., 0.));
60  }
61  else if(model.mJoints[joint_id].mJointType == JointTypeEulerZYX)
62  {
63  double q0 = q[model.mJoints[joint_id].q_index];
64  double q1 = q[model.mJoints[joint_id].q_index + 1];
65  double q2 = q[model.mJoints[joint_id].q_index + 2];
66 
67  double s0 = sin(q0);
68  double c0 = cos(q0);
69  double s1 = sin(q1);
70  double c1 = cos(q1);
71  double s2 = sin(q2);
72  double c2 = cos(q2);
73 
74  model.X_J[joint_id].E = Matrix3d(c0 * c1, s0 * c1, -s1, c0 * s1 * s2 - s0 * c2, s0 * s1 * s2 + c0 * c2, c1 * s2, c0 * s1 * c2 + s0 * s2, s0 * s1 * c2 - c0 * s2, c1 * c2);
75 
76  model.multdof3_S[joint_id](0, 0) = -s1;
77  model.multdof3_S[joint_id](0, 2) = 1.;
78 
79  model.multdof3_S[joint_id](1, 0) = c1 * s2;
80  model.multdof3_S[joint_id](1, 1) = c2;
81 
82  model.multdof3_S[joint_id](2, 0) = c1 * c2;
83  model.multdof3_S[joint_id](2, 1) = -s2;
84 
85  double qdot0 = qdot[model.mJoints[joint_id].q_index];
86  double qdot1 = qdot[model.mJoints[joint_id].q_index + 1];
87  double qdot2 = qdot[model.mJoints[joint_id].q_index + 2];
88 
89  Vector3d qdotv = Vector3d(qdot0, qdot1, qdot2);
90  model.v_J[joint_id].set(model.multdof3_S[joint_id] * qdotv);
91 
92  model.multdof3_S_o[joint_id](0, 0) = -c1 * qdot1;
93  model.multdof3_S_o[joint_id](1, 0) = -s1 * s2 * qdot1 + c1 * c2 * qdot2;
94  model.multdof3_S_o[joint_id](1, 1) = -s2 * qdot2;
95  model.multdof3_S_o[joint_id](2, 0) = -s1 * c2 * qdot1 - c1 * s2 * qdot2;
96  model.multdof3_S_o[joint_id](2, 1) = -c2 * qdot2;
97 
98  model.c_J[joint_id] = model.multdof3_S_o[joint_id]*qdotv;
99  }
100  else if(model.mJoints[joint_id].mJointType == JointTypeEulerXYZ)
101  {
102  double q0 = q[model.mJoints[joint_id].q_index];
103  double q1 = q[model.mJoints[joint_id].q_index + 1];
104  double q2 = q[model.mJoints[joint_id].q_index + 2];
105 
106  double s0 = sin(q0);
107  double c0 = cos(q0);
108  double s1 = sin(q1);
109  double c1 = cos(q1);
110  double s2 = sin(q2);
111  double c2 = cos(q2);
112 
113  model.X_J[joint_id].E = Matrix3d(c2 * c1, s2 * c0 + c2 * s1 * s0, s2 * s0 - c2 * s1 * c0, -s2 * c1, c2 * c0 - s2 * s1 * s0, c2 * s0 + s2 * s1 * c0, s1, -c1 * s0, c1 * c0);
114 
115  model.multdof3_S[joint_id](0, 0) = c2 * c1;
116  model.multdof3_S[joint_id](0, 1) = s2;
117 
118  model.multdof3_S[joint_id](1, 0) = -s2 * c1;
119  model.multdof3_S[joint_id](1, 1) = c2;
120 
121  model.multdof3_S[joint_id](2, 0) = s1;
122  model.multdof3_S[joint_id](2, 2) = 1.;
123 
124  double qdot0 = qdot[model.mJoints[joint_id].q_index];
125  double qdot1 = qdot[model.mJoints[joint_id].q_index + 1];
126  double qdot2 = qdot[model.mJoints[joint_id].q_index + 2];
127 
128  Vector3d qdotv = Vector3d(qdot0, qdot1, qdot2);
129  model.v_J[joint_id].set(model.multdof3_S[joint_id] * qdotv);
130 
131  model.multdof3_S_o[joint_id](0, 0) = -s2 * c1 * qdot2 - c2 * s1 * qdot1;
132  model.multdof3_S_o[joint_id](1, 0) = -c2 * c1 * qdot2 + s2 * s1 * qdot1;
133  model.multdof3_S_o[joint_id](2, 0) = c1 * qdot1;
134  model.multdof3_S_o[joint_id](0, 1) = c2 * qdot2;
135  model.multdof3_S_o[joint_id](1, 1) = -s2 * qdot2;
136 
137  model.c_J[joint_id] = model.multdof3_S_o[joint_id]*qdotv;
138  }
139  else if(model.mJoints[joint_id].mJointType == JointTypeEulerYXZ)
140  {
141  double q0 = q[model.mJoints[joint_id].q_index];
142  double q1 = q[model.mJoints[joint_id].q_index + 1];
143  double q2 = q[model.mJoints[joint_id].q_index + 2];
144 
145  double s0 = sin(q0);
146  double c0 = cos(q0);
147  double s1 = sin(q1);
148  double c1 = cos(q1);
149  double s2 = sin(q2);
150  double c2 = cos(q2);
151 
152  model.X_J[joint_id].E = Matrix3d(c2 * c0 + s2 * s1 * s0, s2 * c1, -c2 * s0 + s2 * s1 * c0, -s2 * c0 + c2 * s1 * s0, c2 * c1, s2 * s0 + c2 * s1 * c0, c1 * s0, -s1, c1 * c0);
153 
154  model.multdof3_S[joint_id](0, 0) = s2 * c1;
155  model.multdof3_S[joint_id](0, 1) = c2;
156 
157  model.multdof3_S[joint_id](1, 0) = c2 * c1;
158  model.multdof3_S[joint_id](1, 1) = -s2;
159 
160  model.multdof3_S[joint_id](2, 0) = -s1;
161  model.multdof3_S[joint_id](2, 2) = 1.;
162 
163  double qdot0 = qdot[model.mJoints[joint_id].q_index];
164  double qdot1 = qdot[model.mJoints[joint_id].q_index + 1];
165  double qdot2 = qdot[model.mJoints[joint_id].q_index + 2];
166 
167  model.multdof3_S_o[joint_id](0, 0) = c2 * c1 * qdot2 - s2 * s1 * qdot1;
168  model.multdof3_S_o[joint_id](0, 1) = -s2 * qdot2;
169  model.multdof3_S_o[joint_id](1, 0) = -s2 * c1 * qdot2 - c2 * s1 * qdot1;
170  model.multdof3_S_o[joint_id](1, 1) = -c2 * qdot2;
171  model.multdof3_S_o[joint_id](2, 0) = -c1 * qdot1;
172 
173  Vector3d qdotv = Vector3d(qdot0,qdot1,qdot2);
174  model.v_J[joint_id].set(model.multdof3_S[joint_id] * qdotv);
175 
176  model.c_J[joint_id] = model.multdof3_S_o[joint_id] * qdotv;
177  }
178  else if(model.mJoints[joint_id].mJointType == JointTypeTranslationXYZ)
179  {
180  double q0 = q[model.mJoints[joint_id].q_index];
181  double q1 = q[model.mJoints[joint_id].q_index + 1];
182  double q2 = q[model.mJoints[joint_id].q_index + 2];
183 
184  model.X_J[joint_id].E = Matrix3d::Identity();
185  model.X_J[joint_id].r = Vector3d(q0, q1, q2);
186 
187  model.multdof3_S[joint_id](3, 0) = 1.;
188  model.multdof3_S[joint_id](4, 1) = 1.;
189  model.multdof3_S[joint_id](5, 2) = 1.;
190 
191  double qdot0 = qdot[model.mJoints[joint_id].q_index];
192  double qdot1 = qdot[model.mJoints[joint_id].q_index + 1];
193  double qdot2 = qdot[model.mJoints[joint_id].q_index + 2];
194 
195  model.v_J[joint_id].set(model.multdof3_S[joint_id] * Vector3d(qdot0, qdot1, qdot2));
196 
197  model.c_J[joint_id].set(0., 0., 0., 0., 0., 0.);
198  }
199  else if(model.mJoints[joint_id].mJointType == JointTypeCustom)
200  {
201  const Joint &joint = model.mJoints[joint_id];
202  CustomJoint *custom_joint = model.mCustomJoints[joint.custom_joint_index];
203  custom_joint->jcalc(model, joint_id, q, qdot);
204  }
205  else
206  {
207  std::cerr << "Error: invalid joint type " << model.mJoints[joint_id].mJointType << " at id " << joint_id << std::endl;
208  abort();
209  }
210 
211  model.bodyFrames[joint_id]->setTransformFromParent(model.X_J[joint_id] * model.X_T[joint_id]);
212  model.bodyFrames[joint_id]->update();
213  }
214 
215  Math::SpatialTransform jcalc_XJ(Model &model, unsigned int joint_id, const Math::VectorNd &q)
216  {
217  // exception if we calculate it for the root body
218  assert (joint_id > 0);
219 
220  if(model.mJoints[joint_id].mDoFCount == 1 && model.mJoints[joint_id].mJointType != JointTypeCustom)
221  {
222  if(model.mJoints[joint_id].mJointType == JointTypeRevolute)
223  {
224  return Xrot(q[model.mJoints[joint_id].q_index], Vector3d(model.mJoints[joint_id].mJointAxes[0][0], model.mJoints[joint_id].mJointAxes[0][1], model.mJoints[joint_id].mJointAxes[0][2]));
225  }
226  else if(model.mJoints[joint_id].mJointType == JointTypePrismatic)
227  {
228  return Xtrans(Vector3d(model.mJoints[joint_id].mJointAxes[0][3] * q[model.mJoints[joint_id].q_index], model.mJoints[joint_id].mJointAxes[0][4] * q[model.mJoints[joint_id].q_index], model.mJoints[joint_id].mJointAxes[0][5] * q[model.mJoints[joint_id].q_index]));
229  }
230  }
231  else
232  {
233  throw RdlException("Error: invalid joint type!");
234  }
235 
236  // Note that these lines are unreachable, but the compiler complains
237  // w/o them about there not being a return in a nonvoid function
238  assert(0);
239  return SpatialTransform();
240  }
241 
242  void jcalc_X_lambda_S(Model &model, unsigned int joint_id, const VectorNd &q)
243  {
244  // exception if we calculate it for the root body
245  assert (joint_id > 0);
246 
247  if(model.mJoints[joint_id].mJointType == JointTypeRevoluteX)
248  {
249  model.X_J[joint_id] = Xrotx(q[model.mJoints[joint_id].q_index]);
250  model.S[joint_id] = model.mJoints[joint_id].mJointAxes[0];
251  }
252  else if(model.mJoints[joint_id].mJointType == JointTypeRevoluteY)
253  {
254  model.X_J[joint_id] = Xroty(q[model.mJoints[joint_id].q_index]);
255  model.S[joint_id] = model.mJoints[joint_id].mJointAxes[0];
256  }
257  else if(model.mJoints[joint_id].mJointType == JointTypeRevoluteZ)
258  {
259  model.X_J[joint_id] = Xrotz(q[model.mJoints[joint_id].q_index]);
260  model.S[joint_id] = model.mJoints[joint_id].mJointAxes[0];
261  }
262  else if(model.mJoints[joint_id].mDoFCount == 1 && model.mJoints[joint_id].mJointType != JointTypeCustom)
263  {
264  model.X_J[joint_id] = jcalc_XJ(model, joint_id, q);
265  // Set the joint axis
266  model.S[joint_id] = model.mJoints[joint_id].mJointAxes[0];
267  }
268  else if(model.mJoints[joint_id].mJointType == JointTypeSpherical)
269  {
270  model.X_J[joint_id] = SpatialTransform(Math::toMatrix(model.GetQuaternion(joint_id, q)), Vector3d(0., 0., 0.));
271 
272  model.multdof3_S[joint_id].setZero();
273 
274  model.multdof3_S[joint_id](0, 0) = 1.;
275  model.multdof3_S[joint_id](1, 1) = 1.;
276  model.multdof3_S[joint_id](2, 2) = 1.;
277  }
278  else if(model.mJoints[joint_id].mJointType == JointTypeEulerZYX)
279  {
280  double q0 = q[model.mJoints[joint_id].q_index];
281  double q1 = q[model.mJoints[joint_id].q_index + 1];
282  double q2 = q[model.mJoints[joint_id].q_index + 2];
283 
284  double s0 = sin(q0);
285  double c0 = cos(q0);
286  double s1 = sin(q1);
287  double c1 = cos(q1);
288  double s2 = sin(q2);
289  double c2 = cos(q2);
290 
291  model.X_J[joint_id] = SpatialTransform(Matrix3d(c0 * c1, s0 * c1, -s1, c0 * s1 * s2 - s0 * c2, s0 * s1 * s2 + c0 * c2, c1 * s2, c0 * s1 * c2 + s0 * s2, s0 * s1 * c2 - c0 * s2, c1 * c2), Vector3d(0., 0., 0.));
292 
293  model.multdof3_S[joint_id].setZero();
294 
295  model.multdof3_S[joint_id](0, 0) = -s1;
296  model.multdof3_S[joint_id](0, 2) = 1.;
297 
298  model.multdof3_S[joint_id](1, 0) = c1 * s2;
299  model.multdof3_S[joint_id](1, 1) = c2;
300 
301  model.multdof3_S[joint_id](2, 0) = c1 * c2;
302  model.multdof3_S[joint_id](2, 1) = -s2;
303  }
304  else if(model.mJoints[joint_id].mJointType == JointTypeEulerXYZ)
305  {
306  double q0 = q[model.mJoints[joint_id].q_index];
307  double q1 = q[model.mJoints[joint_id].q_index + 1];
308  double q2 = q[model.mJoints[joint_id].q_index + 2];
309 
310  double s0 = sin(q0);
311  double c0 = cos(q0);
312  double s1 = sin(q1);
313  double c1 = cos(q1);
314  double s2 = sin(q2);
315  double c2 = cos(q2);
316 
317  model.X_J[joint_id] = SpatialTransform(Matrix3d(c2 * c1, s2 * c0 + c2 * s1 * s0, s2 * s0 - c2 * s1 * c0, -s2 * c1, c2 * c0 - s2 * s1 * s0, c2 * s0 + s2 * s1 * c0, s1, -c1 * s0, c1 * c0), Vector3d(0., 0., 0.));
318 
319  model.multdof3_S[joint_id].setZero();
320 
321  model.multdof3_S[joint_id](0, 0) = c2 * c1;
322  model.multdof3_S[joint_id](0, 1) = s2;
323 
324  model.multdof3_S[joint_id](1, 0) = -s2 * c1;
325  model.multdof3_S[joint_id](1, 1) = c2;
326 
327  model.multdof3_S[joint_id](2, 0) = s1;
328  model.multdof3_S[joint_id](2, 2) = 1.;
329  }
330  else if(model.mJoints[joint_id].mJointType == JointTypeEulerYXZ)
331  {
332  double q0 = q[model.mJoints[joint_id].q_index];
333  double q1 = q[model.mJoints[joint_id].q_index + 1];
334  double q2 = q[model.mJoints[joint_id].q_index + 2];
335 
336  double s0 = sin(q0);
337  double c0 = cos(q0);
338  double s1 = sin(q1);
339  double c1 = cos(q1);
340  double s2 = sin(q2);
341  double c2 = cos(q2);
342 
343  model.X_J[joint_id] = SpatialTransform(Matrix3d(c2 * c0 + s2 * s1 * s0, s2 * c1, -c2 * s0 + s2 * s1 * c0, -s2 * c0 + c2 * s1 * s0, c2 * c1, s2 * s0 + c2 * s1 * c0, c1 * s0, -s1, c1 * c0), Vector3d(0., 0., 0.));
344 
345  model.multdof3_S[joint_id].setZero();
346 
347  model.multdof3_S[joint_id](0, 0) = s2 * c1;
348  model.multdof3_S[joint_id](0, 1) = c2;
349 
350  model.multdof3_S[joint_id](1, 0) = c2 * c1;
351  model.multdof3_S[joint_id](1, 1) = -s2;
352 
353  model.multdof3_S[joint_id](2, 0) = -s1;
354  model.multdof3_S[joint_id](2, 2) = 1.;
355  }
356  else if(model.mJoints[joint_id].mJointType == JointTypeTranslationXYZ)
357  {
358  double q0 = q[model.mJoints[joint_id].q_index];
359  double q1 = q[model.mJoints[joint_id].q_index + 1];
360  double q2 = q[model.mJoints[joint_id].q_index + 2];
361 
362  model.X_J[joint_id] = SpatialTransform(Matrix3d::Identity(3, 3), Vector3d(q0, q1, q2));
363 
364  model.multdof3_S[joint_id].setZero();
365 
366  model.multdof3_S[joint_id](3, 0) = 1.;
367  model.multdof3_S[joint_id](4, 1) = 1.;
368  model.multdof3_S[joint_id](5, 2) = 1.;
369  }
370  else if(model.mJoints[joint_id].mJointType == JointTypeCustom)
371  {
372  const Joint &joint = model.mJoints[joint_id];
373  CustomJoint *custom_joint = model.mCustomJoints[joint.custom_joint_index];
374 
375  custom_joint->jcalc_X_lambda_S(model, joint_id, q);
376  }
377  else
378  {
379  std::cerr << "Error: invalid joint type!" << std::endl;
380  abort();
381  }
382 
383  model.bodyFrames[joint_id]->setTransformFromParent(model.X_J[joint_id] * model.X_T[joint_id]);
384  model.bodyFrames[joint_id]->update();
385  }
386 }
std::vector< Joint > mJoints
All joints.
Definition: Model.h:209
3 DoF joint that uses Euler ZYX convention (faster than emulated
Definition: Joint.h:197
std::vector< Math::SpatialVector > c_J
Definition: Model.h:217
Math::Quaternion GetQuaternion(unsigned int i, const Math::VectorNd &Q) const
Gets the quaternion for body i (only valid if body i is connected by a JointTypeSpherical joint) ...
Definition: Model.h:596
User defined joints of varying size.
Definition: Joint.h:213
CustomJoint is a struct used to create a joint with user defined parameters. This is accomplished by ...
Definition: Joint.h:662
SpatialTransform Xroty(const double &yrot)
Get transform with zero translation and pure rotation about y axis.
SpatialTransform Xtrans(const Vector3d &r)
Get pure translation transform.
void jcalc(Model &model, unsigned int joint_id, const Math::VectorNd &q, const Math::VectorNd &qdot)
Computes all variables for a joint model and updates the body frame as well as the body&#39;s center of m...
Definition: Joint.cc:23
virtual void jcalc_X_lambda_S(Model &model, unsigned int joint_id, const Math::VectorNd &q)=0
std::vector< ReferenceFramePtr > bodyFrames
Definition: Model.h:145
virtual void jcalc(Model &model, unsigned int joint_id, const Math::VectorNd &q, const Math::VectorNd &qdot)=0
SpatialTransform Xrotz(const double &zrot)
Get transform with zero translation and pure rotation about z axis.
Compact representation of spatial transformations.
std::vector< Math::Matrix63 > multdof3_S_o
Definition: Model.h:236
unsigned int custom_joint_index
Definition: Joint.h:635
Describes a joint relative to the predecessor body.
Definition: Joint.h:228
3 DoF joint that uses Euler XYZ convention (faster than emulated
Definition: Joint.h:199
Math::SpatialTransform jcalc_XJ(Model &model, unsigned int joint_id, const Math::VectorNd &q)
Definition: Joint.cc:215
SpatialTransform Xrotx(const double &xrot)
Get transform with zero translation and pure rotation about x axis.
Eigen::VectorXd VectorNd
Definition: rdl_eigenmath.h:25
std::vector< CustomJoint * > mCustomJoints
Definition: Model.h:242
Contains all information about the rigid body model.
Definition: Model.h:121
void jcalc_X_lambda_S(Model &model, unsigned int joint_id, const Math::VectorNd &q)
Definition: Joint.cc:242
A custom exception.
Math::SpatialMotionV v_J
Definition: Model.h:219
std::vector< Math::Matrix63 > multdof3_S
Motion subspace for joints with 3 degrees of freedom.
Definition: Model.h:235
3 DoF joint using Quaternions for joint positional variables and
Definition: Joint.h:195
std::vector< Math::SpatialTransform > X_J
Definition: Model.h:215
static Matrix3d toMatrix(const Quaternion &q)
Convert quaternion to rotation matrix.
Namespace for all structures of the RobotDynamics library.
Definition: Body.h:21
std::vector< Math::SpatialTransform > X_T
Transformations from the parent body to the frame of the joint.
Definition: Model.h:225
Math::MotionVectorV S
Definition: Model.h:211
SpatialTransform Xrot(double angle_rad, const Vector3d &axis)
Get spatial transform from angle and axis.
3 DoF joint that uses Euler YXZ convention (faster than emulated
Definition: Joint.h:201


rdl_dynamics
Author(s):
autogenerated on Tue Apr 20 2021 02:25:27