#include <Eigen/Geometry>
Go to the source code of this file.
◆ get_pose_roll_pitch_yaw()
| Eigen::Vector3d cloe::utility::get_pose_roll_pitch_yaw |
( |
const Eigen::Isometry3d & |
pose | ) |
|
|
inline |
Compute the roll, pitch and yaw angles from a given pose.
- Parameters
-
| pose | Pose of which the rotation matrix shall be expressed in Euler angles. |
◆ pose_from_rotation_translation()
| Eigen::Isometry3d cloe::utility::pose_from_rotation_translation |
( |
const Eigen::Quaterniond & |
quaternion, |
|
|
const Eigen::Vector3d & |
trans |
|
) |
| |
|
inline |
PoseFromRotationTranslation calculates the pose from rotation and translation.
◆ quaternion_from_rpy()
| Eigen::Quaterniond cloe::utility::quaternion_from_rpy |
( |
double |
roll, |
|
|
double |
pitch, |
|
|
double |
yaw |
|
) |
| |
|
inline |
QuaternionFromRPY calculates a quaternion from roll, pitch and yaw.
◆ transform_point_to_child_frame()
| void cloe::utility::transform_point_to_child_frame |
( |
const Eigen::Isometry3d & |
child_frame, |
|
|
Eigen::Vector3d * |
pt_vec |
|
) |
| |
|
inline |
Change a point's frame of reference from the parent frame to the child frame.
- Parameters
-
| child_frame | Pose of the child reference frame w.r.t. the parent frame. |
| pt_vec | Point coordinate vector w.r.t. the parent frame. |
◆ transform_point_to_parent_frame()
| void cloe::utility::transform_point_to_parent_frame |
( |
const Eigen::Isometry3d & |
child_frame, |
|
|
Eigen::Vector3d * |
pt_vec_child |
|
) |
| |
|
inline |
Change a point's frame of reference from the child frame to the parent frame.
- Parameters
-
| child_frame | Pose of the child reference frame w.r.t. the parent frame. |
| pt_vec_child | Point coordinate vector w.r.t. the child frame. |