create_poseπ
Short descriptionπ
create_pose β Create a 3D pose.
Signatureπ
create_pose( real TransX, real TransY, real TransZ, real RotX, real RotY, real RotZ, string OrderOfTransform, string OrderOfRotation, string ViewOfTransform, out pose Pose )
Descriptionπ
create_pose creates the 3D pose Pose. A pose describes a
rigid 3D transformation, i.e., a transformation consisting of an arbitrary
translation and rotation, with 6 parameters: TransX,
TransY, and TransZ specify the translation along the x-,
y-, and z-axis, respectively, while RotX, RotY, and
RotZ describe the rotation.
3D poses are typically used in two ways: First, to describe the position and orientation of one coordinate system relative to another (e.g., the pose of a partβs coordinate system relative to the camera coordinate system - in short: the pose of the part relative to the camera) and secondly, to describe how coordinates can be transformed between two coordinate systems (e.g., to transform points from part coordinates into camera coordinates).
Representation of orientation (rotation)π
A 3D rotation around an arbitrary axis can be represented by 3 parameters in
multiple ways. HALCON lets you choose between three of them with the
parameter OrderOfRotation: If you pass the value 'gba', the
rotation is described by the following chain of rotations around the three
axes (see hom_mat3d_rotate for the content for the rotation matrices
\(\mvAxisRotationMatrixVar{x}{}, \mvAxisRotationMatrixVar{y}{}, and \mvAxisRotationMatrixVar{z}{}\)):
\(\mvAxisRotationMatrixVar{gba}{}\) is referred to as the Yaw-Pitch-Roll convention in the literature. Please note that you can βreadβ this chain in two ways: If you start from the right, the rotations are always performed relative to the global (i.e., fixed or βoldβ) coordinate system. Thus, \(\mvAxisRotationMatrixVar{gba}{}\) can be read as follows: First rotate around the z-axis, then around the βoldβ y-axis, and finally around the βoldβ x-axis. In contrast, if you read from the left to the right, the rotations are performed relative to the local (i.e., βnewβ) coordinate system. Then, \(\mvAxisRotationMatrixVar{gba}{}\) corresponds to the following: First rotate around the x-axis, the around the βnewβ y-axis, and finally around the βnew(est)β z-axis.
Reading \(\mvAxisRotationMatrixVar{gba}{}\) from right to left corresponds to the following sequence of operator calls:
In contrast, reading from left to right corresponds to the following operator sequence:
When passing 'abg' in OrderOfRotation, the rotation
corresponds to the following chain:
\(\mvAxisRotationMatrixVar{abg}{}\) is referred to as the Roll-Pitch-Yaw convention in the literature.
If you pass 'rodriguez' in OrderOfRotation, the rotation
parameters RotX, RotY, and RotZ are interpreted as
the x-, y-, and z-component of the so-called Rodriguez rotation vector. The
direction of the vector defines the (arbitrary) axis of rotation. The length
of the vector usually defines the rotation angle with positive orientation.
Here, a variation of the Rodriguez vector is used, where the length of the
vector defines the tangent of half the rotation angle:
Please note that these 3D poses can be ambiguous, meaning a homogeneous transformation matrix can have several pose representations. For example, for \(\mvAxisRotationMatrixVar{gba}{}\) with \(b=\pm90\) the following poses correspond to the same homogeneous transformation matrix:
| Β |
|---|
create_pose(0, 0, 0, 30, 90, 54, 'Rp+T', 'gba', 'point', Pose1) |
create_pose(0, 0, 0, 17, 90, 67, 'Rp+T', 'gba', 'point', Pose2) |
If this leads to problems, you can instead use homogeneous transformation
matrices or quaternions (axis_angle_to_quat) to represent rotations.
Corresponding homogeneous transformation matrixπ
You can obtain the homogeneous transformation matrix corresponding to a pose
with the operator pose_to_hom_mat3d. In the standard definition, this
is the following homogeneous transformation matrix which can be split into
two separate matrices, one for the translation
(H(T)) and one for the rotation
(H(R)):
Transformation of coordinatesπ
The following equation describes how a point can be transformed from
coordinate system 1 (cs1) into coordinate system 2 (cs2)
with a pose, or more exactly, with the corresponding homogeneous
transformation matrix \(\mvHomMatrixVar{cs2}{cs1}\)
(input and output points as homogeneous vectors, see also
affine_trans_point_3d). Note that to transform points from
cs1 into cs2, you use the transformation matrix that
describes the pose of cs1 relative to cs2.
This corresponds to the following operator calls:
| Β |
|---|
pose_to_hom_mat3d(PoseOf1In2, HomMat3DFrom1In2) |
affine_trans_point_3d(HomMat3DFrom1In2, P1X, P1Y, P1Z, P2X, P2Y, P2Z) |
Non-standard pose definitionsπ
So far, we described the standard pose definition. To create such poses, you
select the (default) values 'Rp+T' for the parameter
OrderOfTransform and 'point' for ViewOfTransform.
By specifying other values for these parameters, you can create non-standard
poses types which we describe briefly below. Please note that these
representation types are only supported for backwards compatibility; we
strongly recommend to use the standard types.
If you select 'R(p-T)' for OrderOfTransform, the created
pose corresponds to the following chain of transformations, i.e., the
sequence of rotation and translation is reversed and the translation is
negated:
If you select 'coordinate_system' for ViewOfTransform, the
sequence of transformations remains constant, but the rotation angles are
negated. Please note that, contrary to its name, this is not equivalent to
transforming a coordinate system!
Returned data structureπ
The created 3D pose is returned in Pose which is a tuple of length
seven. The first three elements hold the translation parameters
TransX, TransY, and TransZ, followed by the
rotation parameters RotX, RotY, and RotZ. The last
element codes the representation type of the pose that you selected with
the parameters OrderOfTransform, OrderOfRotation, and
ViewOfTransform. The following table lists the possible
combinations. As already noted, we recommend to use only the representation
types with OrderOfTransform = 'Rp+T' and
ViewOfTransform = 'point' (codes 0, 2, and 4).
OrderOfTransform |
OrderOfRotation |
ViewOfTransform |
Code |
|---|---|---|---|
| 'Rp+T' | 'gba' | 'point' | 0 |
| 'Rp+T' | 'abg' | 'point' | 2 |
| 'Rp+T' | 'rodriguez' | 'point' | 4 |
| 'Rp+T' | 'gba' | 'coordinate_system' | 1 |
| 'Rp+T' | 'abg' | 'coordinate_system' | 3 |
| 'Rp+T' | 'rodriguez' | 'coordinate_system' | 5 |
| 'R(p-T)' | 'gba' | 'point' | 8 |
| 'R(p-T)' | 'abg' | 'point' | 10 |
| 'R(p-T)' | 'rodriguez' | 'point' | 12 |
| 'R(p-T)' | 'gba' | 'coordinate_system' | 9 |
| 'R(p-T)' | 'abg' | 'coordinate_system' | 11 |
| 'R(p-T)' | 'rodriguez' | 'coordinate_system' | 13 |
You can convert poses into other representation types using
convert_pose_type and query the type using get_pose_type.
Execution informationπ
Execution information
-
Multithreading type: reentrant (runs in parallel with non-exclusive operators).
-
Multithreading scope: global (may be called from any thread).
-
Processed without parallelization.
Parametersπ
TransX (input_control) real β (real)
Translation along the x-axis (in [m]).
Default: 0.1
Suggested values: -1.0, -0.75, -0.5, -0.25, -0.2, -0.1, -0.5, -0.25, -0.125, -0.01, 0.0, 0.01, 0.125, 0.25, 0.5, 0.1, 0.2, 0.25, 0.5, 0.75, 1.0
TransY (input_control) real β (real)
Translation along the y-axis (in [m]).
Default: 0.1
Suggested values: -1.0, -0.75, -0.5, -0.25, -0.2, -0.1, -0.5, -0.25, -0.125, -0.01, 0.0, 0.01, 0.125, 0.25, 0.5, 0.1, 0.2, 0.25, 0.5, 0.75, 1.0
TransZ (input_control) real β (real)
Translation along the z-axis (in [m]).
Default: 0.1
Suggested values: -1.0, -0.75, -0.5, -0.25, -0.2, -0.1, -0.5, -0.25, -0.125, -0.01, 0.0, 0.01, 0.125, 0.25, 0.5, 0.1, 0.2, 0.25, 0.5, 0.75, 1.0
RotX (input_control) real β (real)
Rotation around x-axis or x component of the Rodriguez vector (in [Β°] or without unit).
Default: 90.0
Suggested values: 0.0, 90.0, 180.0, 270.0
Value range: 0 β€ RotX β€ 360
RotY (input_control) real β (real)
Rotation around y-axis or y component of the Rodriguez vector (in [Β°] or without unit).
Default: 90.0
Suggested values: 0.0, 90.0, 180.0, 270.0
Value range: 0 β€ RotY β€ 360
RotZ (input_control) real β (real)
Rotation around z-axis or z component of the Rodriguez vector (in [Β°] or without unit).
Default: 90.0
Suggested values: 0.0, 90.0, 180.0, 270.0
Value range: 0 β€ RotZ β€ 360
OrderOfTransform (input_control) string β (string)
Order of rotation and translation.
Default: 'Rp+T'
Suggested values: 'Rp+T', 'R(p-T)'
OrderOfRotation (input_control) string β (string)
Meaning of the rotation values.
Default: 'gba'
Suggested values: 'gba', 'abg', 'rodriguez'
ViewOfTransform (input_control) string β (string)
View of transformation.
Default: 'point'
Suggested values: 'point', 'coordinate_system'
Pose (output_control) pose β (real / integer)
3D pose.
Number of elements: 7
Exampleπ
(HDevelop)
HTuple Pose, Pose2\;
// Create a pose.
create_pose (0.1, 0.2, 0.3, 40, 50, 60, "Rp+T", "gba", "point", &Pose)\;
Resultπ
create_pose returns 2 (H_MSG_TRUE) if all parameter values are
correct. If necessary, an exception is raised.
Combinations with other operatorsπ
Combinations
Possible successors
pose_to_hom_mat3d, write_pose, camera_calibration, hand_eye_calibration
Alternatives
See also
hom_mat3d_rotate, hom_mat3d_translate, convert_pose_type, get_pose_type, hom_mat3d_to_pose, pose_to_hom_mat3d, write_pose, read_pose
Moduleπ
Foundation