From fe38f757994ff1f0653c49aec33e1d5aaff88887 Mon Sep 17 00:00:00 2001 From: JeroenDM Date: Mon, 28 Sep 2020 08:50:15 +0200 Subject: [PATCH 1/8] add parameterization type to orientation constraints --- msg/OrientationConstraint.msg | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index a79817f..56f78b8 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -8,10 +8,20 @@ geometry_msgs/Quaternion orientation # The robot link this constraint refers to string link_name -# optional axis-angle error tolerances specified +# Optional symmetric error tolerances specified float64 absolute_x_axis_tolerance float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance +# How should we parameterize the optional orientation error tolerance? +# See absolute axis tolerance below to specify the manitude. +uint8 parameterization + +# The different options for the orientation error parameterization +# Intrinsic xyz Euler angles (default value) +uint8 XYZ_EULER_ANGLES=0 +# A rotation vector, the norm represents the rotation angle around this vector +uint8 ROTATION_VECTOR=1 + # A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important) float64 weight From c829a75da30badae4f32d04ee138a1ddd577c32f Mon Sep 17 00:00:00 2001 From: Jeroen Date: Tue, 3 Nov 2020 08:35:38 +0100 Subject: [PATCH 2/8] Apply suggestions from Felix Co-authored-by: Felix von Drigalski --- msg/OrientationConstraint.msg | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index 56f78b8..95462d3 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -13,8 +13,8 @@ float64 absolute_x_axis_tolerance float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance -# How should we parameterize the optional orientation error tolerance? -# See absolute axis tolerance below to specify the manitude. +# Defines how the orientation error is calculated +# See absolute axis tolerance below to specify the magnitude. uint8 parameterization # The different options for the orientation error parameterization From 552e253697edaeb7a9b28c5f4906c64746ca3f42 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Tue, 3 Nov 2020 19:02:49 +0100 Subject: [PATCH 3/8] improve documentation OrientationConstraint msg --- msg/OrientationConstraint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index 95462d3..c04e61e 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -8,7 +8,7 @@ geometry_msgs/Quaternion orientation # The robot link this constraint refers to string link_name -# Optional symmetric error tolerances specified +# Optional tolerance on the three vector components of the orientation error float64 absolute_x_axis_tolerance float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance From cfffda57d2beb54a828475fdc033e2bd9df3bbee Mon Sep 17 00:00:00 2001 From: Jeroen Date: Wed, 4 Nov 2020 08:49:48 +0100 Subject: [PATCH 4/8] punctuation change + replace confusing comment --- msg/OrientationConstraint.msg | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index c04e61e..d133689 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -20,7 +20,8 @@ uint8 parameterization # The different options for the orientation error parameterization # Intrinsic xyz Euler angles (default value) uint8 XYZ_EULER_ANGLES=0 -# A rotation vector, the norm represents the rotation angle around this vector +# A rotation vector. This is similar to the angle-axis representation, +# but the magnitude of the vector represents the rotation angle. uint8 ROTATION_VECTOR=1 # A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important) From 004d788c0888a7e3bf1c3e4775f62e3d2e418ad6 Mon Sep 17 00:00:00 2001 From: JeroenDM Date: Mon, 16 Nov 2020 09:07:58 +0100 Subject: [PATCH 5/8] change below to above --- msg/OrientationConstraint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index d133689..36733fb 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -14,7 +14,7 @@ float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance # Defines how the orientation error is calculated -# See absolute axis tolerance below to specify the magnitude. +# See absolute axis tolerance above to specify the magnitude. uint8 parameterization # The different options for the orientation error parameterization From 180b316a1b9e92c185f51dff4a04487dc6adf3ac Mon Sep 17 00:00:00 2001 From: jeroendm Date: Thu, 19 Nov 2020 08:22:12 +0100 Subject: [PATCH 6/8] format orientation constraint comment --- msg/OrientationConstraint.msg | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index 36733fb..be712bc 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -18,9 +18,9 @@ float64 absolute_z_axis_tolerance uint8 parameterization # The different options for the orientation error parameterization -# Intrinsic xyz Euler angles (default value) +# - Intrinsic xyz Euler angles (default value) uint8 XYZ_EULER_ANGLES=0 -# A rotation vector. This is similar to the angle-axis representation, +# - A rotation vector. This is similar to the angle-axis representation, # but the magnitude of the vector represents the rotation angle. uint8 ROTATION_VECTOR=1 From 490e752eb13d439c000a08ab11e0f29f769deab7 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Thu, 19 Nov 2020 08:24:21 +0100 Subject: [PATCH 7/8] Suggestion Felix comment formulation Co-authored-by: Felix von Drigalski --- msg/OrientationConstraint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index be712bc..27977b8 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -14,7 +14,7 @@ float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance # Defines how the orientation error is calculated -# See absolute axis tolerance above to specify the magnitude. +# The error is compared to the tolerance defined above uint8 parameterization # The different options for the orientation error parameterization From 1f4f230f82b42a8ee010d8fdddf13e4d7acbb9b9 Mon Sep 17 00:00:00 2001 From: Jeroen Date: Thu, 19 Nov 2020 08:28:55 +0100 Subject: [PATCH 8/8] Suggestion Felix, move optional to the end of the sentence Co-authored-by: Felix von Drigalski --- msg/OrientationConstraint.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/OrientationConstraint.msg b/msg/OrientationConstraint.msg index 27977b8..5b57078 100644 --- a/msg/OrientationConstraint.msg +++ b/msg/OrientationConstraint.msg @@ -8,7 +8,7 @@ geometry_msgs/Quaternion orientation # The robot link this constraint refers to string link_name -# Optional tolerance on the three vector components of the orientation error +# Tolerance on the three vector components of the orientation error (optional) float64 absolute_x_axis_tolerance float64 absolute_y_axis_tolerance float64 absolute_z_axis_tolerance