Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add parameterization type to orientation constraints #96

Merged
merged 8 commits into from
Nov 19, 2020
13 changes: 12 additions & 1 deletion msg/OrientationConstraint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,21 @@ geometry_msgs/Quaternion orientation
# The robot link this constraint refers to
string link_name

# optional axis-angle error tolerances specified
# Optional tolerance on the three vector components of the orientation error
JeroenDM marked this conversation as resolved.
Show resolved Hide resolved
float64 absolute_x_axis_tolerance
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.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm good with the content, but shouldn't this new block be moved above the absolute_axis_tolerance entries? This line also assumes they are below.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Oh, good catch, I thought I changed it to above... I will fix it. But about the order:

My reasoning was that if you do not care about the parameterization you don't have to read it. I imagined the file was organized with the important (required) features at the top and the optional less common features at the bottom.

But on the other hand, it is maybe better to first mention how the tolerance values are used before allowing you to specify them.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@felixvd I changed "below" to "above". I assume users start reading at the top of the file, and they can stop reading if they don't care about which parameterization is used. (For small tolerances, or tolerance on a single axis, this does not matter.)

Is this ok?

uint8 parameterization

# The different options for the orientation error parameterization
JeroenDM marked this conversation as resolved.
Show resolved Hide resolved
# Intrinsic xyz Euler angles (default value)
uint8 XYZ_EULER_ANGLES=0
# 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)
float64 weight