Skip to content

Commit

Permalink
Add parameterization type to orientation constraints (#96)
Browse files Browse the repository at this point in the history
* add parameterization type to orientation constraints

* Apply suggestions from Felix

Co-authored-by: Felix von Drigalski <[email protected]>

* improve documentation OrientationConstraint msg

* punctuation change + replace confusing comment

* change below to above

* format orientation constraint comment

* Suggestion Felix comment formulation

Co-authored-by: Felix von Drigalski <[email protected]>

* Suggestion Felix, move optional to the end of the sentence

Co-authored-by: Felix von Drigalski <[email protected]>

Co-authored-by: Felix von Drigalski <[email protected]>
  • Loading branch information
JeroenDM and felixvd authored Nov 19, 2020
1 parent 3175099 commit 1d6168c
Showing 1 changed file with 12 additions and 1 deletion.
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
# 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

# Defines how the orientation error is calculated
# The error is compared to the tolerance defined above
uint8 parameterization

# The different options for the orientation error parameterization
# - 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

0 comments on commit 1d6168c

Please sign in to comment.