robotis_manipulator_math.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Authors: Darby Lim, Hye-Jong KIM, Ryan Shim, Yong-Ho Na */
18 
19 #include "../../include/robotis_manipulator/robotis_manipulator_math.h"
20 
21 /*****************************************************************************
22 ** Make a Vector or Matrix
23 *****************************************************************************/
24 Eigen::Vector3d robotis_manipulator::math::vector3(double v1, double v2, double v3)
25 {
26  Eigen::Vector3d temp;
27  temp << v1, v2, v3;
28  return temp;
29 }
30 
31 Eigen::Matrix3d robotis_manipulator::math::matrix3(double m11, double m12, double m13,
32  double m21, double m22, double m23,
33  double m31, double m32, double m33)
34 {
35  Eigen::Matrix3d temp;
36  temp << m11, m12, m13, m21, m22, m23, m31, m32, m33;
37  return temp;
38 }
39 
40 Eigen::Matrix3d robotis_manipulator::math::inertiaMatrix(double ixx, double ixy, double ixz , double iyy , double iyz, double izz)
41 {
42  Eigen::Matrix3d inertia;
43  inertia <<
44  ixx, ixy, ixz,
45  ixy, iyy, iyz,
46  ixz, iyz, izz;
47 
48  return inertia;
49 }
50 
51 
52 /*****************************************************************************
53 ** Convert
54 *****************************************************************************/
55 // Translation Vector
56 Eigen::Vector3d robotis_manipulator::math::convertXYZToVector(double x, double y, double z)
57 {
58  Eigen::Vector3d position;
59  position << x, y, z;
60 
61  return position;
62 }
63 
64 //Rotation
66 {
67  Eigen::Matrix3d rotation(3,3);
68  rotation <<
69  1.0, 0.0, 0.0,
70  0.0, cos(angle), -sin(angle),
71  0.0, sin(angle), cos(angle);
72 
73  return rotation;
74 }
75 
77 {
78  Eigen::Matrix3d rotation(3,3);
79  rotation <<
80  cos(angle), 0.0, sin(angle),
81  0.0, 1.0, 0.0,
82  -sin(angle), 0.0, cos(angle);
83 
84  return rotation;
85 }
86 
88 {
89  Eigen::Matrix3d rotation(3,3);
90  rotation <<
91  cos(angle), -sin(angle), 0.0,
92  sin(angle), cos(angle), 0.0,
93  0.0, 0.0, 1.0;
94 
95  return rotation;
96 }
97 
98 Eigen::Vector3d robotis_manipulator::math::convertRotationMatrixToRPYVector(const Eigen::Matrix3d& rotation)
99 {
100  Eigen::Vector3d rpy;// = Eigen::MatrixXd::Zero(3,1);
101  rpy.coeffRef(0,0) = atan2(rotation.coeff(2,1), rotation.coeff(2,2));
102  rpy.coeffRef(1,0) = atan2(-rotation.coeff(2,0), sqrt(pow(rotation.coeff(2,1), 2) + pow(rotation.coeff(2,2),2)));
103  rpy.coeffRef(2,0) = atan2 (rotation.coeff(1,0), rotation.coeff(0,0));
104 
105  return rpy;
106 }
107 
108 Eigen::Matrix3d robotis_manipulator::math::convertRPYToRotationMatrix(double roll, double pitch, double yaw)
109 {
111 
112  return rotation;
113 }
114 
115 Eigen::Quaterniond robotis_manipulator::math::convertRPYToQuaternion(double roll, double pitch, double yaw)
116 {
117  Eigen::Quaterniond quaternion;
118  quaternion = robotis_manipulator::math::convertRPYToRotationMatrix(roll,pitch,yaw);
119 
120  return quaternion;
121 }
122 
123 Eigen::Quaterniond robotis_manipulator::math::convertRotationMatrixToQuaternion(const Eigen::Matrix3d& rotation)
124 {
125  Eigen::Quaterniond quaternion;
126  quaternion = rotation;
127 
128  return quaternion;
129 }
130 
131 Eigen::Vector3d robotis_manipulator::math::convertQuaternionToRPYVector(const Eigen::Quaterniond& quaternion)
132 {
133  Eigen::Vector3d rpy = robotis_manipulator::math::convertRotationMatrixToRPYVector(quaternion.toRotationMatrix());
134 
135  return rpy;
136 }
137 
138 Eigen::Matrix3d robotis_manipulator::math::convertQuaternionToRotationMatrix(const Eigen::Quaterniond& quaternion)
139 {
140  Eigen::Matrix3d rotation = quaternion.toRotationMatrix();
141 
142  return rotation;
143 }
144 
145 Eigen::Vector3d robotis_manipulator::math::convertRotationMatrixToOmega(const Eigen::Matrix3d& rotation_matrix)
146 {
147  return robotis_manipulator::math::matrixLogarithm(rotation_matrix);
148 }
149 
150 // Transformation Matrix
151 Eigen::Matrix4d robotis_manipulator::math::convertXYZRPYToTransformationMatrix(double position_x, double position_y, double position_z , double roll , double pitch , double yaw)
152 {
153  Eigen::Matrix4d transformation = robotis_manipulator::math::convertRPYToTransformationMatrix(roll, pitch, yaw);
154  transformation.coeffRef(0,3) = position_x;
155  transformation.coeffRef(1,3) = position_y;
156  transformation.coeffRef(2,3) = position_z;
157 
158  return transformation;
159 }
160 
161 Eigen::Matrix4d robotis_manipulator::math::convertXYZToTransformationMatrix(double position_x, double position_y, double position_z)
162 {
163  Eigen::Matrix4d mat_translation;
164 
165  mat_translation <<
166  1, 0, 0, position_x,
167  0, 1, 0, position_y,
168  0, 0, 1, position_z,
169  0, 0, 0, 1;
170 
171  return mat_translation;
172 }
173 
174 Eigen::Matrix4d robotis_manipulator::math::convertRPYToTransformationMatrix(double roll, double pitch, double yaw )
175 {
176  double sr = sin(roll), cr = cos(roll);
177  double sp = sin(pitch), cp = cos(pitch);
178  double sy = sin(yaw), cy = cos(yaw);
179 
180  Eigen::Matrix4d mat_roll;
181  Eigen::Matrix4d mat_pitch;
182  Eigen::Matrix4d mat_yaw;
183 
184  mat_roll <<
185  1, 0, 0, 0,
186  0, cr, -sr, 0,
187  0, sr, cr, 0,
188  0, 0, 0, 1;
189 
190  mat_pitch <<
191  cp, 0, sp, 0,
192  0, 1, 0, 0,
193  -sp, 0, cp, 0,
194  0, 0, 0, 1;
195 
196  mat_yaw <<
197  cy, -sy, 0, 0,
198  sy, cy, 0, 0,
199  0, 0, 1, 0,
200  0, 0, 0, 1;
201 
202  Eigen::Matrix4d mat_rpy = (mat_yaw*mat_pitch)*mat_roll;
203 
204  return mat_rpy;
205 }
206 
207 Eigen::Matrix4d robotis_manipulator::math::inverseTransformationMatrix(const Eigen::MatrixXd& transform)
208 {
209  // If T is Transform Matrix A from B, the BOA is translation component coordi. B to coordi. A
210 
211  Eigen::Vector3d vec_boa;
212  Eigen::Vector3d vec_x, vec_y, vec_z;
213  Eigen::Matrix4d inv_t;
214 
215  vec_boa(0) = -transform(0,3);
216  vec_boa(1) = -transform(1,3);
217  vec_boa(2) = -transform(2,3);
218 
219  vec_x(0) = transform(0,0); vec_x(1) = transform(1,0); vec_x(2) = transform(2,0);
220  vec_y(0) = transform(0,1); vec_y(1) = transform(1,1); vec_y(2) = transform(2,1);
221  vec_z(0) = transform(0,2); vec_z(1) = transform(1,2); vec_z(2) = transform(2,2);
222 
223  inv_t <<
224  vec_x(0), vec_x(1), vec_x(2), vec_boa.dot(vec_x),
225  vec_y(0), vec_y(1), vec_y(2), vec_boa.dot(vec_y),
226  vec_z(0), vec_z(1), vec_z(2), vec_boa.dot(vec_z),
227  0, 0, 0, 1;
228 
229  return inv_t;
230 }
231 
232 //Dynamic value
233 Eigen::Vector3d robotis_manipulator::math::convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega)
234 {
235  Eigen::Matrix3d c_inverse;
236  Eigen::Vector3d rpy_velocity;
237 
238  c_inverse << 1, sin(rpy_vector(0))*tan(rpy_vector(1)), cos(rpy_vector(0))*tan(rpy_vector(1)),
239  0, cos(rpy_vector(0)), -sin(rpy_vector(0)),
240  0, sin(rpy_vector(0))/cos(rpy_vector(1)), cos(rpy_vector(0))/cos(rpy_vector(1));
241 
242  rpy_velocity = c_inverse * omega;
243  return rpy_velocity;
244 }
245 
246 Eigen::Vector3d robotis_manipulator::math::convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity)
247 {
248  Eigen::Matrix3d c;
249  Eigen::Vector3d omega;
250 
251  c << 1, 0, -sin(rpy_vector(1)),
252  0, cos(rpy_vector(0)), sin(rpy_vector(0))*cos(rpy_vector(1)),
253  0, -sin(rpy_vector(0)), cos(rpy_vector(0))*cos(rpy_vector(1));
254 
255  omega = c * rpy_velocity;
256  return omega;
257 }
258 
259 Eigen::Vector3d robotis_manipulator::math::convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot)
260 {
261  Eigen::Vector3d c_dot;
262  Eigen::Matrix3d c_inverse;
263  Eigen::Vector3d rpy_acceleration;
264 
265  c_dot << -cos(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2],
266  -sin(rpy_vector[0]) * rpy_velocity[0] * rpy_velocity[1] - sin(rpy_vector[0]) * sin(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2] + cos(rpy_vector[0]) * cos(rpy_vector[1]) * rpy_velocity[0] * rpy_velocity[2],
267  -cos(rpy_vector[0]) * rpy_velocity[0] * rpy_velocity[1] - sin(rpy_vector[0]) * cos(rpy_vector[1]) * rpy_velocity[0] * rpy_velocity[2] - cos(rpy_vector[0]) * sin(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2];
268 
269  c_inverse << 1, sin(rpy_vector(0))*tan(rpy_vector(1)), cos(rpy_vector(0))*tan(rpy_vector(1)),
270  0, cos(rpy_vector(0)), -sin(rpy_vector(0)),
271  0, sin(rpy_vector(0))/cos(rpy_vector(1)), cos(rpy_vector(0))/cos(rpy_vector(1));
272 
273  rpy_acceleration = c_inverse * (omega_dot - c_dot);
274  return rpy_acceleration;
275 }
276 
277 Eigen::Vector3d robotis_manipulator::math::convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration)
278 {
279  Eigen::Vector3d c_dot;
280  Eigen::Matrix3d c;
281  Eigen::Vector3d omega_dot;
282 
283  c_dot << -cos(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2],
284  -sin(rpy_vector[0]) * rpy_velocity[0] * rpy_velocity[1] - sin(rpy_vector[0]) * sin(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2] + cos(rpy_vector[0]) * cos(rpy_vector[1]) * rpy_velocity[0] * rpy_velocity[2],
285  -cos(rpy_vector[0]) * rpy_velocity[0] * rpy_velocity[1] - sin(rpy_vector[0]) * cos(rpy_vector[1]) * rpy_velocity[0] * rpy_velocity[2] - cos(rpy_vector[0]) * sin(rpy_vector[1]) * rpy_velocity[1] * rpy_velocity[2];
286 
287  c << 1, 0, -sin(rpy_vector(1)),
288  0, cos(rpy_vector(0)), sin(rpy_vector(0))*cos(rpy_vector(1)),
289  0, -sin(rpy_vector(0)), cos(rpy_vector(0))*cos(rpy_vector(1));
290 
291  omega_dot = c_dot + c * rpy_acceleration;
292  return omega_dot;
293 }
294 
295 
296 /*****************************************************************************
297 ** Math
298 *****************************************************************************/
300 {
301  if (value >= 0.0)
302  {
303  return 1.0;
304  }
305  else
306  {
307  return -1.0;
308  }
309 }
310 
311 Eigen::Vector3d robotis_manipulator::math::matrixLogarithm(Eigen::Matrix3d rotation_matrix)
312 {
313  Eigen::Matrix3d R = rotation_matrix;
314  Eigen::Vector3d l = Eigen::Vector3d::Zero();
315  Eigen::Vector3d rotation_vector = Eigen::Vector3d::Zero();
316 
317  double theta = 0.0;
318  // double diag = 0.0;
319  bool diagonal_matrix = R.isDiagonal();
320 
321  l << R(2, 1) - R(1, 2),
322  R(0, 2) - R(2, 0),
323  R(1, 0) - R(0, 1);
324  theta = atan2(l.norm(), R(0, 0) + R(1, 1) + R(2, 2) - 1);
325  // diag = R.determinant();
326 
327  if (R.isIdentity())
328  {
329  rotation_vector.setZero(3);
330  return rotation_vector;
331  }
332 
333  if (diagonal_matrix == true)
334  {
335  rotation_vector << R(0, 0) + 1, R(1, 1) + 1, R(2, 2) + 1;
336  rotation_vector = rotation_vector * M_PI_2;
337  }
338  else
339  {
340  rotation_vector = theta * (l / l.norm());
341  }
342  return rotation_vector;
343 }
344 
345 Eigen::Matrix3d robotis_manipulator::math::skewSymmetricMatrix(Eigen::Vector3d v)
346 {
347  Eigen::Matrix3d skew_symmetric_matrix = Eigen::Matrix3d::Zero();
348  skew_symmetric_matrix << 0, -v(2), v(1),
349  v(2), 0, -v(0),
350  -v(1), v(0), 0;
351  return skew_symmetric_matrix;
352 }
353 
354 Eigen::Matrix3d robotis_manipulator::math::rodriguesRotationMatrix(Eigen::Vector3d axis, double angle)
355 {
356  Eigen::Matrix3d skew_symmetric_matrix = Eigen::Matrix3d::Zero();
357  Eigen::Matrix3d rotation_matrix = Eigen::Matrix3d::Zero();
358  Eigen::Matrix3d Identity_matrix = Eigen::Matrix3d::Identity();
359 
360  skew_symmetric_matrix = robotis_manipulator::math::skewSymmetricMatrix(axis);
361  rotation_matrix = Identity_matrix +
362  skew_symmetric_matrix * sin(angle) +
363  skew_symmetric_matrix * skew_symmetric_matrix * (1 - cos(angle));
364  return rotation_matrix;
365 }
366 
367 Eigen::Vector3d robotis_manipulator::math::positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position)
368 {
369  Eigen::Vector3d position_difference;
370  position_difference = desired_position - present_position;
371 
372  return position_difference;
373 }
374 
375 Eigen::Vector3d robotis_manipulator::math::orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
376 {
377  Eigen::Vector3d orientation_difference;
378  orientation_difference = present_orientation * robotis_manipulator::math::matrixLogarithm(present_orientation.transpose() * desired_orientation);
379 
380  return orientation_difference;
381 }
382 
383 Eigen::VectorXd robotis_manipulator::math::poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position,
384  Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
385 {
386  Eigen::Vector3d position_difference;
387  Eigen::Vector3d orientation_difference;
388  Eigen::VectorXd pose_difference(6);
389 
390  position_difference = robotis_manipulator::math::positionDifference(desired_position, present_position);
391  orientation_difference = robotis_manipulator::math::orientationDifference(desired_orientation, present_orientation);
392  pose_difference << position_difference(0), position_difference(1), position_difference(2),
393  orientation_difference(0), orientation_difference(1), orientation_difference(2);
394 
395  return pose_difference;
396 }
397 
398 Eigen::VectorXd robotis_manipulator::math::dynamicPoseDifference(Eigen::Vector3d desired_linear_velocity, Eigen::Vector3d present_linear_velocity, Eigen::Vector3d desired_angular_velocity, Eigen::Vector3d present_angular_velocity)
399 {
400  Eigen::Vector3d linear_difference = desired_linear_velocity - present_linear_velocity;
401  Eigen::Vector3d angular_difference = desired_angular_velocity - present_angular_velocity;
402  Eigen::VectorXd dynamic_pose_difference(6);
403  dynamic_pose_difference << linear_difference(0), linear_difference(1), linear_difference(2),
404  angular_difference(0), angular_difference(1), angular_difference(2);
405 
406  return dynamic_pose_difference;
407 }
Eigen::Matrix4d convertRPYToTransformationMatrix(double roll, double pitch, double yaw)
Eigen::Matrix3d inertiaMatrix(double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
Eigen::VectorXd dynamicPoseDifference(Eigen::Vector3d desired_linear_velocity, Eigen::Vector3d present_linear_velocity, Eigen::Vector3d desired_angular_velocity, Eigen::Vector3d present_angular_velocity)
Eigen::Vector3d convertQuaternionToRPYVector(const Eigen::Quaterniond &quaternion)
Eigen::Vector3d convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity)
Eigen::VectorXd poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position, Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
Eigen::Matrix3d matrix3(double m11, double m12, double m13, double m21, double m22, double m23, double m31, double m32, double m33)
Eigen::Vector3d convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration)
Eigen::Matrix3d convertQuaternionToRotationMatrix(const Eigen::Quaterniond &quaternion)
Eigen::Matrix4d inverseTransformationMatrix(const Eigen::MatrixXd &transformation_matrix)
Eigen::Vector3d orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
Eigen::Vector3d vector3(double v1, double v2, double v3)
Eigen::Vector3d convertRotationMatrixToOmega(const Eigen::Matrix3d &rotation_matrix)
Eigen::Matrix3d skewSymmetricMatrix(Eigen::Vector3d v)
Eigen::Vector3d positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position)
Eigen::Vector3d matrixLogarithm(Eigen::Matrix3d rotation_matrix)
Eigen::Matrix3d rodriguesRotationMatrix(Eigen::Vector3d axis, double angle)
Eigen::Matrix4d convertXYZRPYToTransformationMatrix(double x, double y, double z, double roll, double pitch, double yaw)
Eigen::Vector3d convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega)
Eigen::Vector3d convertXYZToVector(double x, double y, double z)
Eigen::Quaterniond convertRPYToQuaternion(double roll, double pitch, double yaw)
Eigen::Matrix3d convertRollAngleToRotationMatrix(double angle)
Eigen::Vector3d convertRotationMatrixToRPYVector(const Eigen::Matrix3d &rotation_matrix)
Eigen::Vector3d convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot)
Eigen::Matrix3d convertYawAngleToRotationMatrix(double angle)
Eigen::Matrix3d convertPitchAngleToRotationMatrix(double angle)
Eigen::Matrix3d convertRPYToRotationMatrix(double roll, double pitch, double yaw)
Eigen::Matrix4d convertXYZToTransformationMatrix(double x, double y, double z)
Eigen::Quaterniond convertRotationMatrixToQuaternion(const Eigen::Matrix3d &rotation_matrix)


robotis_manipulator
Author(s): Hye-Jong KIM , Darby Lim , Yong-Ho Na , Ryan Shim
autogenerated on Sat Oct 3 2020 03:14:51