#include <Eigen/Dense>
#include <limits>
Go to the source code of this file.
|
void | orca::math::setToHighest (Eigen::VectorXd &v) |
|
template<typename T > |
bool | orca::math::equal (const T &a, const T &b) |
|
void | orca::math::setToLowest (Eigen::VectorXd &v) |
|
Eigen::Vector3d | orca::math::diffRot (const Eigen::Matrix3d &R_a_b1, const Eigen::Matrix3d &R_a_b2) |
|
Eigen::Matrix< double, 6, 1 > | orca::math::diffTransform (const Eigen::Matrix4d &t_a_b1, const Eigen::Matrix4d &t_a_b2) |
|
Eigen::Quaterniond | orca::math::quatFromRPY (double roll, double pitch, double yaw) |
|
Eigen::Quaterniond | orca::math::quatFromKukaConvention (double A, double B, double C) |
|
Eigen::Matrix< double, 6, 1 > & | orca::math::transportWrench (const Eigen::Matrix< double, 6, 1 > &wrench_in_a, const Eigen::Matrix< double, 3, 1 > &b_to_a, Eigen::Matrix< double, 6, 1 > &wrench_in_b_out) |
|