| Classes | |
| class | BezierCurve | 
| class | FifthOrderPolynomialTrajectory | 
| class | MinimumJerk | 
| class | MinimumJerkViaPoint | 
| struct | Point2D | 
| struct | Pose3D | 
| struct | Position3D | 
| class | PreviewControl | 
| class | SimpleTrapezoidalVelocityProfile | 
| struct | StepData | 
| struct | StepPositionData | 
| struct | StepTimeData | 
| Functions | |
| Eigen::MatrixXd | calcArc3dTra (double smp_time, double mov_time, Eigen::MatrixXd center_point, Eigen::MatrixXd normal_vector, Eigen::MatrixXd start_point, double rotation_angle, double cross_ratio) | 
| Eigen::Vector3d | calcCross (const Eigen::Vector3d &vector3d_a, const Eigen::Vector3d &vector3d_b) | 
| Eigen::Matrix3d | calcHatto (const Eigen::Vector3d &matrix3d) | 
| double | calcInner (const Eigen::MatrixXd &vector3d_a, const Eigen::MatrixXd &vector3d_b) | 
| double | calcInner (Eigen::MatrixXd vector3d_a, Eigen::MatrixXd vector3d_b) | 
| Eigen::MatrixXd | calcMinimumJerkTra (double pos_start, double vel_start, double accel_start, double pos_end, double vel_end, double accel_end, double smp_time, double mov_time) | 
| Eigen::MatrixXd | calcMinimumJerkTraPlus (double pos_start, double vel_start, double accel_start, double pos_end, double vel_end, double accel_end, double smp_time, double mov_time) | 
| Eigen::MatrixXd | calcMinimumJerkTraWithViaPoints (int via_num, double pos_start, double vel_start, double accel_start, Eigen::MatrixXd pos_via, Eigen::MatrixXd vel_via, Eigen::MatrixXd accel_via, double pos_end, double vel_end, double accel_end, double smp_time, Eigen::MatrixXd via_time, double mov_time) | 
| Eigen::MatrixXd | calcMinimumJerkTraWithViaPointsPosition (int via_num, double pos_start, double vel_start, double accel_start, Eigen::MatrixXd pos_via, double pos_end, double vel_end, double accel_end, double smp_time, Eigen::MatrixXd via_time, double mov_time) | 
| Eigen::Matrix3d | calcRodrigues (const Eigen::Matrix3d &hat_matrix, double angle) | 
| int | combination (int n, int r) | 
| Eigen::Matrix3d | convertQuaternionToRotation (const Eigen::Quaterniond &quaternion) | 
| Eigen::Vector3d | convertQuaternionToRPY (const Eigen::Quaterniond &quaternion) | 
| Eigen::Quaterniond | convertRotationToQuaternion (const Eigen::Matrix3d &rotation) | 
| Eigen::Vector3d | convertRotationToRPY (const Eigen::Matrix3d &rotation) | 
| Eigen::Vector3d | convertRotToOmega (const Eigen::Matrix3d &rotation) | 
| Eigen::Quaterniond | convertRPYToQuaternion (double roll, double pitch, double yaw) | 
| Eigen::Matrix3d | convertRPYToRotation (double roll, double pitch, double yaw) | 
| std::string | dispatchMovingFoot (int moving_foot) | 
| std::string | dispatchWalkingState (int walking_state) | 
| Eigen::Matrix3d | getInertiaXYZ (double ixx, double ixy, double ixz, double iyy, double iyz, double izz) | 
| Eigen::Matrix4d | getInverseTransformation (const Eigen::MatrixXd &transform) | 
| Pose3D | getPose3DfromTransformMatrix (const Eigen::Matrix4d &transform) | 
| Eigen::Matrix4d | getRotation4d (double roll, double pitch, double yaw) | 
| Eigen::Matrix3d | getRotationX (double angle) | 
| Eigen::Matrix3d | getRotationY (double angle) | 
| Eigen::Matrix3d | getRotationZ (double angle) | 
| Eigen::Matrix4d | getTransformationXYZRPY (double position_x, double position_y, double position_z, double roll, double pitch, double yaw) | 
| Eigen::Vector3d | getTransitionXYZ (double position_x, double position_y, double position_z) | 
| Eigen::Matrix4d | getTranslation4D (double position_x, double position_y, double position_z) | 
| std::ostream & | operator<< (std::ostream &out, const Pose3D &pose) | 
| std::ostream & | operator<< (std::ostream &out, const StepPositionData &position_data) | 
| std::ostream & | operator<< (std::ostream &out, const StepTimeData &time_data) | 
| std::ostream & | operator<< (std::ostream &out, const StepData &step_data) | 
| double | powDI (double a, int b) | 
| double | sign (double x) | 
| Eigen::MatrixXd robotis_framework::calcArc3dTra | ( | double | smp_time, | 
| double | mov_time, | ||
| Eigen::MatrixXd | center_point, | ||
| Eigen::MatrixXd | normal_vector, | ||
| Eigen::MatrixXd | start_point, | ||
| double | rotation_angle, | ||
| double | cross_ratio | ||
| ) | 
Definition at line 507 of file robotis_trajectory_calculator.cpp.
| Eigen::Vector3d robotis_framework::calcCross | ( | const Eigen::Vector3d & | vector3d_a, | 
| const Eigen::Vector3d & | vector3d_b | ||
| ) | 
Definition at line 273 of file robotis_linear_algebra.cpp.
| Eigen::Matrix3d robotis_framework::calcHatto | ( | const Eigen::Vector3d & | matrix3d | ) | 
Definition at line 218 of file robotis_linear_algebra.cpp.
| double robotis_framework::calcInner | ( | const Eigen::MatrixXd & | vector3d_a, | 
| const Eigen::MatrixXd & | vector3d_b | ||
| ) | 
| double robotis_framework::calcInner | ( | Eigen::MatrixXd | vector3d_a, | 
| Eigen::MatrixXd | vector3d_b | ||
| ) | 
Definition at line 285 of file robotis_linear_algebra.cpp.
| Eigen::MatrixXd robotis_framework::calcMinimumJerkTra | ( | double | pos_start, | 
| double | vel_start, | ||
| double | accel_start, | ||
| double | pos_end, | ||
| double | vel_end, | ||
| double | accel_end, | ||
| double | smp_time, | ||
| double | mov_time | ||
| ) | 
Definition at line 29 of file robotis_trajectory_calculator.cpp.
| Eigen::MatrixXd robotis_framework::calcMinimumJerkTraPlus | ( | double | pos_start, | 
| double | vel_start, | ||
| double | accel_start, | ||
| double | pos_end, | ||
| double | vel_end, | ||
| double | accel_end, | ||
| double | smp_time, | ||
| double | mov_time | ||
| ) | 
Definition at line 88 of file robotis_trajectory_calculator.cpp.
| Eigen::MatrixXd robotis_framework::calcMinimumJerkTraWithViaPoints | ( | int | via_num, | 
| double | pos_start, | ||
| double | vel_start, | ||
| double | accel_start, | ||
| Eigen::MatrixXd | pos_via, | ||
| Eigen::MatrixXd | vel_via, | ||
| Eigen::MatrixXd | accel_via, | ||
| double | pos_end, | ||
| double | vel_end, | ||
| double | accel_end, | ||
| double | smp_time, | ||
| Eigen::MatrixXd | via_time, | ||
| double | mov_time | ||
| ) | 
Definition at line 160 of file robotis_trajectory_calculator.cpp.
| Eigen::MatrixXd robotis_framework::calcMinimumJerkTraWithViaPointsPosition | ( | int | via_num, | 
| double | pos_start, | ||
| double | vel_start, | ||
| double | accel_start, | ||
| Eigen::MatrixXd | pos_via, | ||
| double | pos_end, | ||
| double | vel_end, | ||
| double | accel_end, | ||
| double | smp_time, | ||
| Eigen::MatrixXd | via_time, | ||
| double | mov_time | ||
| ) | 
Definition at line 353 of file robotis_trajectory_calculator.cpp.
| Eigen::Matrix3d robotis_framework::calcRodrigues | ( | const Eigen::Matrix3d & | hat_matrix, | 
| double | angle | ||
| ) | 
Definition at line 230 of file robotis_linear_algebra.cpp.
| int robotis_framework::combination | ( | int | n, | 
| int | r | ||
| ) | 
Definition at line 32 of file robotis_math_base.cpp.
| Eigen::Matrix3d robotis_framework::convertQuaternionToRotation | ( | const Eigen::Quaterniond & | quaternion | ) | 
Definition at line 211 of file robotis_linear_algebra.cpp.
| Eigen::Vector3d robotis_framework::convertQuaternionToRPY | ( | const Eigen::Quaterniond & | quaternion | ) | 
Definition at line 204 of file robotis_linear_algebra.cpp.
| Eigen::Quaterniond robotis_framework::convertRotationToQuaternion | ( | const Eigen::Matrix3d & | rotation | ) | 
Definition at line 196 of file robotis_linear_algebra.cpp.
| Eigen::Vector3d robotis_framework::convertRotationToRPY | ( | const Eigen::Matrix3d & | rotation | ) | 
Definition at line 170 of file robotis_linear_algebra.cpp.
| Eigen::Vector3d robotis_framework::convertRotToOmega | ( | const Eigen::Matrix3d & | rotation | ) | 
Definition at line 242 of file robotis_linear_algebra.cpp.
| Eigen::Quaterniond robotis_framework::convertRPYToQuaternion | ( | double | roll, | 
| double | pitch, | ||
| double | yaw | ||
| ) | 
Definition at line 188 of file robotis_linear_algebra.cpp.
| Eigen::Matrix3d robotis_framework::convertRPYToRotation | ( | double | roll, | 
| double | pitch, | ||
| double | yaw | ||
| ) | 
Definition at line 181 of file robotis_linear_algebra.cpp.
| std::string robotis_framework::dispatchMovingFoot | ( | int | moving_foot | ) | 
Definition at line 23 of file step_data_define.cpp.
| std::string robotis_framework::dispatchWalkingState | ( | int | walking_state | ) | 
Definition at line 34 of file step_data_define.cpp.
| Eigen::Matrix3d robotis_framework::getInertiaXYZ | ( | double | ixx, | 
| double | ixy, | ||
| double | ixz, | ||
| double | iyy, | ||
| double | iyz, | ||
| double | izz | ||
| ) | 
Definition at line 76 of file robotis_linear_algebra.cpp.
| Eigen::Matrix4d robotis_framework::getInverseTransformation | ( | const Eigen::MatrixXd & | transform | ) | 
Definition at line 51 of file robotis_linear_algebra.cpp.
| Pose3D robotis_framework::getPose3DfromTransformMatrix | ( | const Eigen::Matrix4d & | transform | ) | 
Definition at line 290 of file robotis_linear_algebra.cpp.
| Eigen::Matrix4d robotis_framework::getRotation4d | ( | double | roll, | 
| double | pitch, | ||
| double | yaw | ||
| ) | 
Definition at line 124 of file robotis_linear_algebra.cpp.
| Eigen::Matrix3d robotis_framework::getRotationX | ( | double | angle | ) | 
Definition at line 88 of file robotis_linear_algebra.cpp.
| Eigen::Matrix3d robotis_framework::getRotationY | ( | double | angle | ) | 
Definition at line 100 of file robotis_linear_algebra.cpp.
| Eigen::Matrix3d robotis_framework::getRotationZ | ( | double | angle | ) | 
Definition at line 112 of file robotis_linear_algebra.cpp.
| Eigen::Matrix4d robotis_framework::getTransformationXYZRPY | ( | double | position_x, | 
| double | position_y, | ||
| double | position_z, | ||
| double | roll, | ||
| double | pitch, | ||
| double | yaw | ||
| ) | 
Definition at line 41 of file robotis_linear_algebra.cpp.
| Eigen::Vector3d robotis_framework::getTransitionXYZ | ( | double | position_x, | 
| double | position_y, | ||
| double | position_z | ||
| ) | 
Definition at line 29 of file robotis_linear_algebra.cpp.
| Eigen::Matrix4d robotis_framework::getTranslation4D | ( | double | position_x, | 
| double | position_y, | ||
| double | position_z | ||
| ) | 
Definition at line 157 of file robotis_linear_algebra.cpp.
| std::ostream & robotis_framework::operator<< | ( | std::ostream & | out, | 
| const Pose3D & | pose | ||
| ) | 
Definition at line 45 of file step_data_define.cpp.
| std::ostream & robotis_framework::operator<< | ( | std::ostream & | out, | 
| const StepPositionData & | position_data | ||
| ) | 
Definition at line 50 of file step_data_define.cpp.
| std::ostream & robotis_framework::operator<< | ( | std::ostream & | out, | 
| const StepTimeData & | time_data | ||
| ) | 
Definition at line 63 of file step_data_define.cpp.
| std::ostream & robotis_framework::operator<< | ( | std::ostream & | out, | 
| const StepData & | step_data | ||
| ) | 
Definition at line 73 of file step_data_define.cpp.
| 
 | inline | 
Definition at line 39 of file robotis_math_base.h.
| double robotis_framework::sign | ( | double | x | ) | 
Definition at line 22 of file robotis_math_base.cpp.