|
|
using | MatrixType = Eigen::Matrix3d |
| |
|
|
template<typename Container , typename = std::enable_if_t<std::is_same_v<typename Container::value_type, MatrixType>>> |
| static std::optional< MatrixType > | Average (const Container &matrices, double eps, int max_iter=-1) |
| |
|
static MatrixType | Exp (so3v::MatrixType w, double angle=1.0) |
| |
|
static MatrixType | FromEulerAngle (const Eigen::Vector3d &angles, EulerAngleType type) |
| |
|
static MatrixType | FromQuaternion (const Eigen::Quaterniond &q) |
| |
| static MatrixType | FromRPY (const Eigen::Vector3d &angles) |
| |
|
static Eigen::Vector3d | GetX (const MatrixType &R) |
| |
|
static Eigen::Vector3d | GetY (const MatrixType &R) |
| |
|
static Eigen::Vector3d | GetZ (const MatrixType &R) |
| |
|
static so3::MatrixType | Hat (const so3v::MatrixType &w) |
| |
|
static MatrixType | Identity () |
| |
|
static MatrixType | Inverse (const MatrixType &R) |
| |
|
static so3v::MatrixType | Log (const MatrixType &R) |
| |
|
static MatrixType | Projection (const MatrixType &m) |
| |
|
static MatrixType | RotX (double angle) |
| |
|
static MatrixType | RotY (double angle) |
| |
|
static MatrixType | RotZ (double angle) |
| |
|
static Eigen::Vector3d | ToEulerAngle (const MatrixType &R, EulerAngleType type) |
| |
|
static Eigen::Quaterniond | ToQuaternion (const MatrixType &R) |
| |
| static Eigen::Vector3d | ToRPY (const MatrixType &R) |
| |
|
static so3v::MatrixType | Vec (const so3::MatrixType &r) |
| |
◆ FromRPY()
| static MatrixType rb::math::SO3::FromRPY |
( |
const Eigen::Vector3d & | angles | ) |
|
|
static |
Calculate rotation from roll, pitch and yqw angles
- Parameters
-
| angles | [0] roll [1] pitch [2] yaw |
- Returns
◆ ToRPY()
| static Eigen::Vector3d rb::math::SO3::ToRPY |
( |
const MatrixType & | R | ) |
|
|
static |
- Parameters
-
- Returns
- [0] roll [1] pitch [2] yaw
The documentation for this class was generated from the following file:
- /external/rby1-sdk/include/rby1-sdk/math/so3.h