I think it could be useful to add an extra field to the message for orientation constraints that specifies how the orientation should be parameterized when testing the constraints. Currently, the tolerances are applied to the XYZ Euler angles (intrinsic rotations), but they could be just as well be applied to any three number parameterization.
While working on #2092, I seem to notice that exponential coordinates (rotation angle * rotation axis) performed better for projection-based sampling.
My proposal would be to add something like this:
# How should the orientation be parameterized with three numbers
# the absolute axis tolerances are applied to these numbers
uint8 parameterization
# The different options for the orientation constraint parameterization
uint8 XYZ_EULER_ANGLES=0
uint8 EXPONENTIAL_COORDINATES=1
Edit An alternative proposed by @felixvd is to use separate fields for the two different tolerances.
# (optional) Angle tolerance. Only one of the below representation may be used. Not all solvers may support all of them.
# in Euler angles
float64 absolute_x_axis_tolerance
float64 absolute_y_axis_tolerance
float64 absolute_z_axis_tolerance
# in exponential coordinates [add link or explanation here]
float64 value_1
float64 value_2
float64 value_3
The implementation in kinematic_constraints.cpp could look like this: (we would also need to update the constraint samplers)
ConstraintEvaluationResult OrientationConstraint::decide(const moveit::core::RobotState& state, bool verbose) const
{
/* ... some other code ... */
Eigen::Isometry3d diff(desired_rotation_matrix_inv_ * state.getGlobalLinkTransform(link_model_).linear());
if (parameterization_ == Parameterization::EXPONENTIAL_COORDINATES)
{
angle_axis = Eigen::AngleAxisd(diff.linear());
xyz = angle_axis.axis() * angle_axis.angle();
xyz(0) = fabs(xyz(0));
xyz(1) = fabs(xyz(1));
xyz(2) = fabs(xyz(2));
}
else if (parameterization_ == Parameterization::XYZ_EULER_ANGLES)
{
// use Euler angles by default
// 0,1,2 corresponds to XYZ, the convention used in sampling constraints
xyz = diff.linear().eulerAngles(0, 1, 2);
xyz(0) = std::min(fabs(xyz(0)), boost::math::constants::pi<double>() - fabs(xyz(0)));
xyz(1) = std::min(fabs(xyz(1)), boost::math::constants::pi<double>() - fabs(xyz(1)));
xyz(2) = std::min(fabs(xyz(2)), boost::math::constants::pi<double>() - fabs(xyz(2)));
}
else
{ /*default */ }
}
bool result = xyz(2) < absolute_z_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
xyz(1) < absolute_y_axis_tolerance_ + std::numeric_limits<double>::epsilon() &&
xyz(0) < absolute_x_axis_tolerance_ + std::numeric_limits<double>::epsilon();
/* ... some other code ... */
}
A typical planning problem where we want to keep a gripper level to the ground, that can also be solved with the new constraints.
![ur_glass_upright](https://user-images.githubusercontent.com/11537861/91064418-83f5d900-e62f-11ea-865d-b6bf511a145d.gif)
This problem could also be specified using tolerances on Euler angles, but for planners that don't like Euler angles, it is useful to have this alternative. For example, TrajOpt does not use Euler angles.