Namespaces | Macros | Functions
robotis_linear_algebra.h File Reference
#include <cmath>
#include <eigen3/Eigen/Dense>
#include "step_data_define.h"
Include dependency graph for robotis_linear_algebra.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 robotis_framework
 

Macros

#define EIGEN_NO_DEBUG
 
#define EIGEN_NO_STATIC_ASSERT
 

Functions

Eigen::Vector3d robotis_framework::calcCross (const Eigen::Vector3d &vector3d_a, const Eigen::Vector3d &vector3d_b)
 
Eigen::Matrix3d robotis_framework::calcHatto (const Eigen::Vector3d &matrix3d)
 
double robotis_framework::calcInner (const Eigen::MatrixXd &vector3d_a, const Eigen::MatrixXd &vector3d_b)
 
Eigen::Matrix3d robotis_framework::calcRodrigues (const Eigen::Matrix3d &hat_matrix, double angle)
 
Eigen::Matrix3d robotis_framework::convertQuaternionToRotation (const Eigen::Quaterniond &quaternion)
 
Eigen::Vector3d robotis_framework::convertQuaternionToRPY (const Eigen::Quaterniond &quaternion)
 
Eigen::Quaterniond robotis_framework::convertRotationToQuaternion (const Eigen::Matrix3d &rotation)
 
Eigen::Vector3d robotis_framework::convertRotationToRPY (const Eigen::Matrix3d &rotation)
 
Eigen::Vector3d robotis_framework::convertRotToOmega (const Eigen::Matrix3d &rotation)
 
Eigen::Quaterniond robotis_framework::convertRPYToQuaternion (double roll, double pitch, double yaw)
 
Eigen::Matrix3d robotis_framework::convertRPYToRotation (double roll, double pitch, double yaw)
 
Eigen::Matrix3d robotis_framework::getInertiaXYZ (double ixx, double ixy, double ixz, double iyy, double iyz, double izz)
 
Eigen::Matrix4d robotis_framework::getInverseTransformation (const Eigen::MatrixXd &transform)
 
Pose3D robotis_framework::getPose3DfromTransformMatrix (const Eigen::Matrix4d &transform)
 
Eigen::Matrix4d robotis_framework::getRotation4d (double roll, double pitch, double yaw)
 
Eigen::Matrix3d robotis_framework::getRotationX (double angle)
 
Eigen::Matrix3d robotis_framework::getRotationY (double angle)
 
Eigen::Matrix3d robotis_framework::getRotationZ (double angle)
 
Eigen::Matrix4d robotis_framework::getTransformationXYZRPY (double position_x, double position_y, double position_z, double roll, double pitch, double yaw)
 
Eigen::Vector3d robotis_framework::getTransitionXYZ (double position_x, double position_y, double position_z)
 
Eigen::Matrix4d robotis_framework::getTranslation4D (double position_x, double position_y, double position_z)
 

Macro Definition Documentation

#define EIGEN_NO_DEBUG

Definition at line 27 of file robotis_linear_algebra.h.

#define EIGEN_NO_STATIC_ASSERT

Definition at line 28 of file robotis_linear_algebra.h.



robotis_math
Author(s): SCH , Kayman , Jay Song
autogenerated on Fri Jul 17 2020 03:17:50