Robotis Manipulator  1.0.0
robotis_manipulator_math.h
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 
25 #ifndef ROBOTIS_MANIPULATOR_MATH_H_
26 #define ROBOTIS_MANIPULATOR_MATH_H_
27 
28 #include <unistd.h>
29 
30 #if defined(__OPENCR__)
31  #include <Eigen.h> // Calls main Eigen matrix class library
32  #include <Eigen/LU> // Calls inverse, determinant, LU decomp., etc.
33  #include <Eigen/Geometry>
34 #else
35  #include <eigen3/Eigen/Eigen>
36  #include <eigen3/Eigen/LU>
37 #endif
38 
39 #include <math.h>
40 
41 #define DEG2RAD 0.01745329252 //(M_PI / 180.0)
42 #define RAD2DEG 57.2957795131 //(180.0 / M_PI)
43 
44 namespace robotis_manipulator
45 {
46 
47 namespace math {
48 
49 /*****************************************************************************
50 ** Make a Vector or Matrix
51 *****************************************************************************/
59 Eigen::Vector3d vector3(double v1, double v2, double v3);
73 Eigen::Matrix3d matrix3(double m11, double m12, double m13,
74  double m21, double m22, double m23,
75  double m31, double m32, double m33);
86 Eigen::Matrix3d inertiaMatrix(double ixx, double ixy, double ixz , double iyy , double iyz, double izz);
87 
88 
89 /*****************************************************************************
90 ** Convert
91 *****************************************************************************/
92 // Translation Vector
100 Eigen::Vector3d convertXYZToVector(double x, double y, double z);
101 
102 // Rotation
108 Eigen::Matrix3d convertRollAngleToRotationMatrix(double angle);
114 Eigen::Matrix3d convertPitchAngleToRotationMatrix(double angle);
120 Eigen::Matrix3d convertYawAngleToRotationMatrix(double angle);
126 Eigen::Vector3d convertRotationMatrixToRPYVector(const Eigen::Matrix3d& rotation_matrix);
134 Eigen::Matrix3d convertRPYToRotationMatrix(double roll, double pitch, double yaw);
142 Eigen::Quaterniond convertRPYToQuaternion(double roll, double pitch, double yaw);
148 Eigen::Quaterniond convertRotationMatrixToQuaternion(const Eigen::Matrix3d& rotation_matrix);
154 Eigen::Vector3d convertQuaternionToRPYVector(const Eigen::Quaterniond& quaternion);
160 Eigen::Matrix3d convertQuaternionToRotationMatrix(const Eigen::Quaterniond& quaternion);
166 Eigen::Vector3d convertRotationMatrixToOmega(const Eigen::Matrix3d& rotation_matrix);
167 
168 // Transformation Matrix
179 Eigen::Matrix4d convertXYZRPYToTransformationMatrix(double x, double y, double z , double roll, double pitch, double yaw);
187 Eigen::Matrix4d convertXYZToTransformationMatrix(double x, double y, double z);
195 Eigen::Matrix4d convertRPYToTransformationMatrix(double roll, double pitch, double yaw);
196 
197 // Dynamic Value
204 Eigen::Vector3d convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega);
211 Eigen::Vector3d convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity);
219 Eigen::Vector3d convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot);
227 Eigen::Vector3d convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration);
228 
229 
230 /*****************************************************************************
231 ** Math
232 *****************************************************************************/
238 double sign(double value);
239 
245 Eigen::Matrix4d inverseTransformationMatrix(const Eigen::MatrixXd& transformation_matrix);
251 Eigen::Vector3d matrixLogarithm(Eigen::Matrix3d rotation_matrix);
257 Eigen::Matrix3d skewSymmetricMatrix(Eigen::Vector3d v);
264 Eigen::Matrix3d rodriguesRotationMatrix(Eigen::Vector3d axis, double angle);
265 
272 Eigen::Vector3d positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position);
279 Eigen::Vector3d orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation);
288 Eigen::VectorXd poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position,
289  Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation);
290 
291 } // math
292 } // namespace robotis_manipulator
293 
294 #endif // ROBOTIS_MANIPULATOR_MATH_H_
Eigen::Matrix4d convertRPYToTransformationMatrix(double roll, double pitch, double yaw)
convertRPYToTransformationMatrix
double sign(double value)
sign
Eigen::Matrix3d inertiaMatrix(double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
inertiaMatrix
main namespace
Eigen::Vector3d convertQuaternionToRPYVector(const Eigen::Quaterniond &quaternion)
convertQuaternionToRPYVector
Eigen::Vector3d convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity)
convertRPYVelocityToOmega
Eigen::VectorXd poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position, Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
poseDifference
Eigen::Matrix3d matrix3(double m11, double m12, double m13, double m21, double m22, double m23, double m31, double m32, double m33)
matrix3
Eigen::Vector3d convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration)
convertRPYAccelerationToOmegaDot
Eigen::Matrix3d convertQuaternionToRotationMatrix(const Eigen::Quaterniond &quaternion)
convertQuaternionToRotationMatrix
Eigen::Matrix4d inverseTransformationMatrix(const Eigen::MatrixXd &transformation_matrix)
inverseTransformationMatrix
Eigen::Vector3d orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
orientationDifference
Eigen::Vector3d vector3(double v1, double v2, double v3)
vector3
Eigen::Vector3d convertRotationMatrixToOmega(const Eigen::Matrix3d &rotation_matrix)
convertRotationMatrixToOmega
Eigen::Matrix3d skewSymmetricMatrix(Eigen::Vector3d v)
skewSymmetricMatrix
Eigen::Vector3d positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position)
positionDifference
Eigen::Vector3d matrixLogarithm(Eigen::Matrix3d rotation_matrix)
matrixLogarithm
Eigen::Matrix3d rodriguesRotationMatrix(Eigen::Vector3d axis, double angle)
rodriguesRotationMatrix
Eigen::Matrix4d convertXYZRPYToTransformationMatrix(double x, double y, double z, double roll, double pitch, double yaw)
convertXYZRPYToTransformationMatrix
Eigen::Vector3d convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega)
convertOmegaToRPYVelocity
Eigen::Vector3d convertXYZToVector(double x, double y, double z)
convertXYZToVector
Eigen::Quaterniond convertRPYToQuaternion(double roll, double pitch, double yaw)
convertRPYToQuaternion
Eigen::Matrix3d convertRollAngleToRotationMatrix(double angle)
convertRollAngleToRotationMatrix
Eigen::Vector3d convertRotationMatrixToRPYVector(const Eigen::Matrix3d &rotation_matrix)
convertRotationMatrixToRPYVector
Eigen::Vector3d convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot)
convertOmegaDotToRPYAcceleration
Eigen::Matrix3d convertYawAngleToRotationMatrix(double angle)
convertYawAngleToRotationMatrix
Eigen::Matrix3d convertPitchAngleToRotationMatrix(double angle)
convertPitchAngleToRotationMatrix
Eigen::Matrix3d convertRPYToRotationMatrix(double roll, double pitch, double yaw)
convertRPYToRotationMatrix
Eigen::Matrix4d convertXYZToTransformationMatrix(double x, double y, double z)
convertXYZToTransformationMatrix
Eigen::Quaterniond convertRotationMatrixToQuaternion(const Eigen::Matrix3d &rotation_matrix)
convertRotationMatrixToQuaternion