$darkmode
geometry.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020 Robert Bosch GmbH
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  * SPDX-License-Identifier: Apache-2.0
17  */
22 #pragma once
23 
24 #include <Eigen/Geometry>
25 
26 namespace cloe {
27 namespace utility {
28 
32 inline Eigen::Quaterniond quaternion_from_rpy(double roll, double pitch, double yaw) {
33  // ZYX body flxed rotations
34  Eigen::Quaterniond qt = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) *
35  Eigen::AngleAxisd(pitch, Eigen::Vector3d::UnitY()) *
36  Eigen::AngleAxisd(roll, Eigen::Vector3d::UnitX());
37  return qt;
38 }
39 
43 inline Eigen::Isometry3d pose_from_rotation_translation(const Eigen::Quaterniond& quaternion,
44  const Eigen::Vector3d& trans) {
45  Eigen::Isometry3d pose;
46  pose.setIdentity();
47  pose.linear() = quaternion.matrix();
48  pose.translation() = trans;
49  return pose;
50 }
51 
57 inline Eigen::Vector3d get_pose_roll_pitch_yaw(const Eigen::Isometry3d& pose) {
58  return pose.rotation().matrix().eulerAngles(2, 1, 0).reverse();
59 }
60 
67 inline void transform_point_to_child_frame(const Eigen::Isometry3d& child_frame,
68  Eigen::Vector3d* pt_vec) {
69  *pt_vec = child_frame.inverse() * (*pt_vec);
70 }
71 
78 inline void transform_point_to_parent_frame(const Eigen::Isometry3d& child_frame,
79  Eigen::Vector3d* pt_vec_child) {
80  *pt_vec_child = child_frame * (*pt_vec_child);
81 }
82 
83 } // namespace utility
84 } // namespace cloe
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