24 #include <Eigen/Geometry>
34 Eigen::Quaterniond qt = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
35 Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
36 Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
44 const Eigen::Vector3d& trans) {
45 Eigen::Isometry3d pose;
47 pose.linear() = quaternion.matrix();
48 pose.translation() = trans;
58 return pose.rotation().matrix().eulerAngles(2, 1, 0).reverse();
68 Eigen::Vector3d* pt_vec) {
69 *pt_vec = child_frame.inverse() * (*pt_vec);
79 Eigen::Vector3d* pt_vec_child) {
80 *pt_vec_child = child_frame * (*pt_vec_child);
Eigen::Quaterniond quaternion_from_rpy(double roll, double pitch, double yaw)
Definition: geometry.hpp:32
Eigen::Vector3d get_pose_roll_pitch_yaw(const Eigen::Isometry3d &pose)
Definition: geometry.hpp:57
void transform_point_to_child_frame(const Eigen::Isometry3d &child_frame, Eigen::Vector3d *pt_vec)
Definition: geometry.hpp:67
void transform_point_to_parent_frame(const Eigen::Isometry3d &child_frame, Eigen::Vector3d *pt_vec_child)
Definition: geometry.hpp:78
Eigen::Isometry3d pose_from_rotation_translation(const Eigen::Quaterniond &quaternion, const Eigen::Vector3d &trans)
Definition: geometry.hpp:43