Introduced in version 0.14.0
<aside> 💡
This document describes the various ways to define a 3D pose (translation + orientation) in Exwayz YAML configuration files.
</aside>
# 4x4 matrix (row major)
matrix: [1.0, 0.0, 0.0, 0.0,
0.0, 1.0, 0.0, 0.0,
0.0, 0.0, 1.0, 0.0,
0.0, 0.0, 0.0, 1.0]
# [optional] offset added to the pose to handle large geographic coordinates
offset: [0.0, 0.0, 0.0]
$$ T = \begin{pmatrix} R & u \\ 0 & 1 \\ \end{pmatrix} \in SE(3) \\
R \in SO(3) \\ u \in \mathbb{R}^3 $$
# translation in meters
translation: [1.0, 2.0, 3.0]
# euler angles [Rx, Ry, Rz] (roll, pitch yaw)
euler: [0.0, 0.0, 90.0]
# boolean switch, if true euler angles are interpreted as degrees, otherwise,
# they are interpreted as radians (default: true)
angles_degrees: true
# [optional] offset added to the pose to handle large geographic coordinates
offset: [0.0, 0.0, 0.0]
$$ R(\theta_x, \theta_y, \theta_z)=R_z(\theta_z) \; R_y(\theta_y) \; R_x(\theta_x) $$
$$ R_x(\theta)=\begin{pmatrix} 1 & 0 & 0 \\ 0 & \cos \theta & -\sin \theta \\ 1 & \sin \theta & \cos \theta \\ \end{pmatrix} $$
$$ R_y(\theta)=\begin{pmatrix} \cos \theta & 0 & \sin \theta \\ 0 & 1 & 0 \\ -\sin \theta & 0 & \cos \theta \\ \end{pmatrix} $$
$$ R_z(\theta)=\begin{pmatrix} \cos \theta & -\sin \theta & 0 \\ \sin \theta & \cos \theta & 0 \\ 0 & 0 & 1 \\ \end{pmatrix} $$
# translation in meters
translation: [1.0, 2.0, 3.0]
# orientation as quaternion
quaternion: [1.0, 0.0, 0.0, 0.0]
# [optional] offset added to the pose to handle large geographic coordinates
offset: [0.0, 0.0, 0.0]
Quaternions are defined in Hamilton convention $q=\left(q_w,\, q_x,\, q_y,\, q_z \right)$.
⚠️ this is different from JPL convention used in ROS $q=\left(q_x,\, q_y,\, q_z,\, q_w \right)$.