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 
19 #ifndef ROBOTIS_MANIPULATOR_MATH_H_
20 #define ROBOTIS_MANIPULATOR_MATH_H_
21 
22 #include <unistd.h>
23 
24 #if defined(__OPENCR__)
25  #include <Eigen.h> // Calls main Eigen matrix class library
26  #include <Eigen/LU> // Calls inverse, determinant, LU decomp., etc.
27  #include <Eigen/Geometry>
28 #else
29  #include <eigen3/Eigen/Eigen>
30  #include <eigen3/Eigen/LU>
31 #endif
32 
33 #include <math.h>
34 
35 #define DEG2RAD 0.01745329252 //(M_PI / 180.0)
36 #define RAD2DEG 57.2957795131 //(180.0 / M_PI)
37 
38 namespace robotis_manipulator
39 {
40 
41 namespace math {
42 
43 /*****************************************************************************
44 ** Make a Vector or Matrix
45 *****************************************************************************/
46 Eigen::Vector3d vector3(double v1, double v2, double v3);
47 Eigen::Matrix3d matrix3(double m11, double m12, double m13,
48  double m21, double m22, double m23,
49  double m31, double m32, double m33);
50 Eigen::Matrix3d inertiaMatrix(double ixx, double ixy, double ixz , double iyy , double iyz, double izz);
51 
52 
53 /*****************************************************************************
54 ** Convert
55 *****************************************************************************/
56 // Translation Vector
57 Eigen::Vector3d convertXYZToVector(double x, double y, double z);
58 
59 // Rotation
60 Eigen::Matrix3d convertRollAngleToRotationMatrix(double angle);
61 Eigen::Matrix3d convertPitchAngleToRotationMatrix(double angle);
62 Eigen::Matrix3d convertYawAngleToRotationMatrix(double angle);
63 Eigen::Vector3d convertRotationMatrixToRPYVector(const Eigen::Matrix3d& rotation_matrix);
64 Eigen::Matrix3d convertRPYToRotationMatrix(double roll, double pitch, double yaw);
65 Eigen::Quaterniond convertRPYToQuaternion(double roll, double pitch, double yaw);
66 Eigen::Quaterniond convertRotationMatrixToQuaternion(const Eigen::Matrix3d& rotation_matrix);
67 Eigen::Vector3d convertQuaternionToRPYVector(const Eigen::Quaterniond& quaternion);
68 Eigen::Matrix3d convertQuaternionToRotationMatrix(const Eigen::Quaterniond& quaternion);
69 Eigen::Vector3d convertRotationMatrixToOmega(const Eigen::Matrix3d& rotation_matrix);
70 
71 // Transformation Matrix
72 Eigen::Matrix4d convertXYZRPYToTransformationMatrix(double x, double y, double z , double roll, double pitch, double yaw);
73 Eigen::Matrix4d convertXYZToTransformationMatrix(double x, double y, double z);
74 Eigen::Matrix4d convertRPYToTransformationMatrix(double roll, double pitch, double yaw);
75 
76 // Dynamic Value
77 Eigen::Vector3d convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega);
78 Eigen::Vector3d convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity);
79 Eigen::Vector3d convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot);
80 Eigen::Vector3d convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration);
81 
82 
83 /*****************************************************************************
84 ** Math
85 *****************************************************************************/
86 double sign(double value);
87 
88 Eigen::Matrix4d inverseTransformationMatrix(const Eigen::MatrixXd& transformation_matrix);
89 Eigen::Vector3d matrixLogarithm(Eigen::Matrix3d rotation_matrix);
90 Eigen::Matrix3d skewSymmetricMatrix(Eigen::Vector3d v);
91 Eigen::Matrix3d rodriguesRotationMatrix(Eigen::Vector3d axis, double angle);
92 
93 Eigen::Vector3d positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position);
94 Eigen::Vector3d orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation);
95 Eigen::VectorXd poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position,
96  Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation);
97 Eigen::VectorXd dynamicPoseDifference(Eigen::Vector3d desired_linear_velocity, Eigen::Vector3d present_linear_velocity,
98  Eigen::Vector3d desired_angular_velocity, Eigen::Vector3d present_angular_velocity);
99 
100 } // math
101 } // namespace robotis_manipulator
102 
103 #endif // ROBOTIS_MANIPULATOR_MATH_H_
robotis_manipulator::math::sign
double sign(double value)
Definition: robotis_manipulator_math.cpp:299
robotis_manipulator::math::convertRPYToQuaternion
Eigen::Quaterniond convertRPYToQuaternion(double roll, double pitch, double yaw)
Definition: robotis_manipulator_math.cpp:115
robotis_manipulator::math::convertXYZToTransformationMatrix
Eigen::Matrix4d convertXYZToTransformationMatrix(double x, double y, double z)
Definition: robotis_manipulator_math.cpp:161
robotis_manipulator::math::convertRollAngleToRotationMatrix
Eigen::Matrix3d convertRollAngleToRotationMatrix(double angle)
Definition: robotis_manipulator_math.cpp:65
robotis_manipulator::math::matrix3
Eigen::Matrix3d matrix3(double m11, double m12, double m13, double m21, double m22, double m23, double m31, double m32, double m33)
Definition: robotis_manipulator_math.cpp:31
robotis_manipulator::math::convertYawAngleToRotationMatrix
Eigen::Matrix3d convertYawAngleToRotationMatrix(double angle)
Definition: robotis_manipulator_math.cpp:87
robotis_manipulator::math::inverseTransformationMatrix
Eigen::Matrix4d inverseTransformationMatrix(const Eigen::MatrixXd &transformation_matrix)
Definition: robotis_manipulator_math.cpp:207
robotis_manipulator::math::convertRPYToTransformationMatrix
Eigen::Matrix4d convertRPYToTransformationMatrix(double roll, double pitch, double yaw)
Definition: robotis_manipulator_math.cpp:174
robotis_manipulator::math::convertRotationMatrixToOmega
Eigen::Vector3d convertRotationMatrixToOmega(const Eigen::Matrix3d &rotation_matrix)
Definition: robotis_manipulator_math.cpp:145
robotis_manipulator::math::convertRPYVelocityToOmega
Eigen::Vector3d convertRPYVelocityToOmega(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity)
Definition: robotis_manipulator_math.cpp:246
robotis_manipulator::math::positionDifference
Eigen::Vector3d positionDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position)
Definition: robotis_manipulator_math.cpp:367
robotis_manipulator::math::poseDifference
Eigen::VectorXd poseDifference(Eigen::Vector3d desired_position, Eigen::Vector3d present_position, Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
Definition: robotis_manipulator_math.cpp:383
robotis_manipulator::math::matrixLogarithm
Eigen::Vector3d matrixLogarithm(Eigen::Matrix3d rotation_matrix)
Definition: robotis_manipulator_math.cpp:311
robotis_manipulator::math::convertXYZRPYToTransformationMatrix
Eigen::Matrix4d convertXYZRPYToTransformationMatrix(double x, double y, double z, double roll, double pitch, double yaw)
Definition: robotis_manipulator_math.cpp:151
robotis_manipulator::math::convertOmegaToRPYVelocity
Eigen::Vector3d convertOmegaToRPYVelocity(Eigen::Vector3d rpy_vector, Eigen::Vector3d omega)
Definition: robotis_manipulator_math.cpp:233
robotis_manipulator::math::inertiaMatrix
Eigen::Matrix3d inertiaMatrix(double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
Definition: robotis_manipulator_math.cpp:40
robotis_manipulator
Definition: robotis_manipulator.h:30
robotis_manipulator::math::skewSymmetricMatrix
Eigen::Matrix3d skewSymmetricMatrix(Eigen::Vector3d v)
Definition: robotis_manipulator_math.cpp:345
robotis_manipulator::math::dynamicPoseDifference
Eigen::VectorXd dynamicPoseDifference(Eigen::Vector3d desired_linear_velocity, Eigen::Vector3d present_linear_velocity, Eigen::Vector3d desired_angular_velocity, Eigen::Vector3d present_angular_velocity)
Definition: robotis_manipulator_math.cpp:398
robotis_manipulator::math::convertXYZToVector
Eigen::Vector3d convertXYZToVector(double x, double y, double z)
Definition: robotis_manipulator_math.cpp:56
robotis_manipulator::math::convertQuaternionToRPYVector
Eigen::Vector3d convertQuaternionToRPYVector(const Eigen::Quaterniond &quaternion)
Definition: robotis_manipulator_math.cpp:131
robotis_manipulator::math::orientationDifference
Eigen::Vector3d orientationDifference(Eigen::Matrix3d desired_orientation, Eigen::Matrix3d present_orientation)
Definition: robotis_manipulator_math.cpp:375
robotis_manipulator::math::vector3
Eigen::Vector3d vector3(double v1, double v2, double v3)
Definition: robotis_manipulator_math.cpp:24
robotis_manipulator::math::convertRotationMatrixToRPYVector
Eigen::Vector3d convertRotationMatrixToRPYVector(const Eigen::Matrix3d &rotation_matrix)
Definition: robotis_manipulator_math.cpp:98
robotis_manipulator::math::convertPitchAngleToRotationMatrix
Eigen::Matrix3d convertPitchAngleToRotationMatrix(double angle)
Definition: robotis_manipulator_math.cpp:76
robotis_manipulator::math::convertQuaternionToRotationMatrix
Eigen::Matrix3d convertQuaternionToRotationMatrix(const Eigen::Quaterniond &quaternion)
Definition: robotis_manipulator_math.cpp:138
robotis_manipulator::math::convertRPYToRotationMatrix
Eigen::Matrix3d convertRPYToRotationMatrix(double roll, double pitch, double yaw)
Definition: robotis_manipulator_math.cpp:108
robotis_manipulator::math::convertOmegaDotToRPYAcceleration
Eigen::Vector3d convertOmegaDotToRPYAcceleration(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d omega_dot)
Definition: robotis_manipulator_math.cpp:259
robotis_manipulator::math::rodriguesRotationMatrix
Eigen::Matrix3d rodriguesRotationMatrix(Eigen::Vector3d axis, double angle)
Definition: robotis_manipulator_math.cpp:354
robotis_manipulator::math::convertRPYAccelerationToOmegaDot
Eigen::Vector3d convertRPYAccelerationToOmegaDot(Eigen::Vector3d rpy_vector, Eigen::Vector3d rpy_velocity, Eigen::Vector3d rpy_acceleration)
Definition: robotis_manipulator_math.cpp:277
robotis_manipulator::math::convertRotationMatrixToQuaternion
Eigen::Quaterniond convertRotationMatrixToQuaternion(const Eigen::Matrix3d &rotation_matrix)
Definition: robotis_manipulator_math.cpp:123


robotis_manipulator
Author(s): Hye-Jong KIM , Darby Lim , Yong-Ho Na , Ryan Shim
autogenerated on Wed Mar 2 2022 00:50:56