四元数基础知识
目标: 了解 ROS 2 中四元数使用的基础知识。
教程级别: 中级
时间: 10 分钟
背景
四元数是方向的 4 元组表示,比旋转矩阵更简洁。 四元数非常适用于分析涉及三维旋转的情况。 四元数广泛应用于机器人技术、量子力学、计算机视觉和 3D 动画。
您可以在 Wikipedia 上了解有关底层数学概念的更多信息。 您还可以查看由 3blue1brown 制作的可探索视频系列 Visualizing quaternions。
在本教程中,您将了解四元数和转换方法在 ROS 2 中的工作原理。
先决条件
但是,这不是硬性要求,您可以坚持使用最适合您的任何其他几何变换库。 您可以查看 transforms3d、scipy.spatial.transform、pytransform3d、numpy-quaternion 或 blender.mathutils 等库。
四元数的分量
ROS 2 使用四元数来跟踪和应用旋转。
四元数有 4 个分量 (x, y, z, w)
。
在 ROS 2 中,“w” 位于最后,但在 Eigen 等一些库中,“w” 可以放在第一个位置。
不绕 x/y/z 轴旋转的常用单位四元数是“(0, 0, 0, 1)”,可以按以下方式创建:
#include <tf2/LinearMath/Quaternion.h>
...
tf2::Quaternion q;
// Create a quaternion from roll/pitch/yaw in radians (0, 0, 0)
q.setRPY(0, 0, 0);
// Print the quaternion components (0, 0, 0, 1)
RCLCPP_INFO(this->get_logger(), "%f %f %f %f",
q.x(), q.y(), q.z(), q.w());
四元数的量级应始终为 1。 如果数值错误导致四元数量级不为 1,ROS 2 将打印警告。 为了避免这些警告,请对四元数进行规范化:
q.normalize();
ROS 2 中的四元数类型
ROS 2 使用两种四元数数据类型:“tf2::Quaternion”及其等效的“geometry_msgs::msg::Quaternion”。
要在 C++ 中在它们之间进行转换,请使用“tf2_geometry_msgs”的方法。
C++
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
...
tf2::Quaternion tf2_quat, tf2_quat_from_msg;
tf2_quat.setRPY(roll, pitch, yaw);
// Convert tf2::Quaternion to geometry_msgs::msg::Quaternion
geometry_msgs::msg::Quaternion msg_quat = tf2::toMsg(tf2_quat);
// Convert geometry_msgs::msg::Quaternion to tf2::Quaternion
tf2::convert(msg_quat, tf2_quat_from_msg);
// or
tf2::fromMsg(msg_quat, tf2_quat_from_msg);
Python
from geometry_msgs.msg import Quaternion
...
# Create a list of floats, which is compatible with tf2
# Quaternion methods
quat_tf = [0.0, 1.0, 0.0, 0.0]
# Convert a list to geometry_msgs.msg.Quaternion
msg_quat = Quaternion(x=quat_tf[0], y=quat_tf[1], z=quat_tf[2], w=quat_tf[3])
四元数运算
1 用 RPY 思考,然后转换为四元数
我们很容易想到绕轴的旋转,但很难用四元数来思考。 建议以滚动(绕 X 轴)、俯仰(绕 Y 轴)和偏航(绕 Z 轴)的形式计算目标旋转,然后转换为四元数。
# quaternion_from_euler method is available in turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py
q = quaternion_from_euler(1.5707, 0, -1.5707)
print(f'The quaternion representation is x: {q[0]} y: {q[1]} z: {q[2]} w: {q[3]}.')
2 应用四元数旋转
要将一个四元数的旋转应用于姿势,只需将该姿势的前一个四元数乘以表示所需旋转的四元数即可。 此乘法的顺序很重要。
C++
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
...
tf2::Quaternion q_orig, q_rot, q_new;
q_orig.setRPY(0.0, 0.0, 0.0);
// Rotate the previous pose by 180* about X
q_rot.setRPY(3.14159, 0.0, 0.0);
q_new = q_rot * q_orig;
q_new.normalize();
Python
q_orig = quaternion_from_euler(0, 0, 0)
# Rotate the previous pose by 180* about X
q_rot = quaternion_from_euler(3.14159, 0, 0)
q_new = quaternion_multiply(q_rot, q_orig)
3 反转四元数
反转四元数的一个简单方法是对 w 分量取反:
q[3] = -q[3]
4 相对旋转
假设您有两个来自同一帧的四元数,q_1
和 q_2
。
您想找到相对旋转,q_r
,以以下方式将``q_1`` 转换为``q_2``:
q_2 = q_r * q_1
你可以像求解矩阵方程一样求解“q r”。 求“q_1”的逆,然后右乘两边。同样,乘法的顺序很重要:
q_r = q_2 * q_1_inverse
下面是一个使用 Python 获取从前一个机器人姿势到当前机器人姿势的相对旋转的示例:
def quaternion_multiply(q0, q1):
"""
Multiplies two quaternions.
Input
:param q0: A 4 element array containing the first quaternion (q01, q11, q21, q31)
:param q1: A 4 element array containing the second quaternion (q02, q12, q22, q32)
Output
:return: A 4 element array containing the final quaternion (q03,q13,q23,q33)
"""
# Extract the values from q0
w0 = q0[0]
x0 = q0[1]
y0 = q0[2]
z0 = q0[3]
# Extract the values from q1
w1 = q1[0]
x1 = q1[1]
y1 = q1[2]
z1 = q1[3]
# Computer the product of the two quaternions, term by term
q0q1_w = w0 * w1 - x0 * x1 - y0 * y1 - z0 * z1
q0q1_x = w0 * x1 + x0 * w1 + y0 * z1 - z0 * y1
q0q1_y = w0 * y1 - x0 * z1 + y0 * w1 + z0 * x1
q0q1_z = w0 * z1 + x0 * y1 - y0 * x1 + z0 * w1
# Create a 4 element array containing the final quaternion
final_quaternion = np.array([q0q1_w, q0q1_x, q0q1_y, q0q1_z])
# Return a 4 element array containing the final quaternion (q02,q12,q22,q32)
return final_quaternion
q1_inv[0] = prev_pose.pose.orientation.x
q1_inv[1] = prev_pose.pose.orientation.y
q1_inv[2] = prev_pose.pose.orientation.z
q1_inv[3] = -prev_pose.pose.orientation.w # Negate for inverse
q2[0] = current_pose.pose.orientation.x
q2[1] = current_pose.pose.orientation.y
q2[2] = current_pose.pose.orientation.z
q2[3] = current_pose.pose.orientation.w
qr = quaternion_multiply(q2, q1_inv)
摘要
在本教程中,您了解了四元数的基本概念及其相关的数学运算,如反转和旋转。 您还了解了它在 ROS 2 中的使用示例以及两个单独的四元数类之间的转换方法。