Skip to content

Commit

Permalink
Fix orientation constraints (moveit#3656)
Browse files Browse the repository at this point in the history
The tolerance of orientation constraints needs to be interpreted w.r.t. the given frame_id of the constraint instead of the target frame. Not doing so, a large tolerance is interpreted about the wrong axis and resolving constraint frames fails.
Unfortunately, the proposed approach only works for the ROTATION_VECTOR representation.
  • Loading branch information
rhaschke authored Oct 31, 2024
1 parent 4b01062 commit 0a93db3
Show file tree
Hide file tree
Showing 5 changed files with 91 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -497,6 +497,9 @@ bool IKConstraintSampler::samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& q
moveit_msgs::OrientationConstraint::ROTATION_VECTOR)
{
Eigen::Vector3d rotation_vector(angle_x, angle_y, angle_z);
// convert rotation vector from frame_id to target frame
rotation_vector =
sampling_pose_.orientation_constraint_->getDesiredRotationMatrixInRefFrame().transpose() * rotation_vector;
diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
}
else
Expand All @@ -506,14 +509,9 @@ bool IKConstraintSampler::samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& q
"The parameterization type for the orientation constraints is invalid.");
}

// diff is isometry by construction
// getDesiredRotationMatrix() returns a valid rotation matrix by contract
// reqr has thus to be a valid isometry
Eigen::Isometry3d reqr(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());
quat = Eigen::Quaterniond(reqr.linear()); // reqr is isometry, so quat has to be normalized
quat = Eigen::Quaterniond(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());

// if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
// model
// if this constraint is with respect to a mobile frame, we need to convert this rotation to the root frame of the model
if (sampling_pose_.orientation_constraint_->mobileReferenceFrame())
{
// getFrameTransform() returns a valid isometry by contract
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -337,12 +337,19 @@ MOVEIT_CLASS_FORWARD(OrientationConstraint); // Defines OrientationConstraintPt
/**
* \brief Class for constraints on the orientation of a link
*
* This class expresses an orientation constraint on a particular
* link. The constraint is specified in terms of a quaternion, with
* tolerances on X,Y, and Z axes. The rotation difference is computed
* based on the XYZ Euler angle formulation (intrinsic rotations) or as a rotation vector. This depends on the
* `Parameterization` type. The header on the quaternion can be specified in terms of either a fixed or a mobile
* frame. The type value will return ORIENTATION_CONSTRAINT.
* This class expresses an orientation constraint on a particular link.
* The constraint specifies a target orientation via a quaternion as well as
* tolerances on X,Y, and Z rotation axes.
* The rotation difference between the target and actual link orientation is expressed
* either as XYZ Euler angles or as a rotation vector (depending on the `parameterization` type).
* The latter is highly recommended, because it supports resolution of subframes and attached bodies.
* Also, rotation vector representation allows to interpret the tolerances always w.r.t. the given reference frame.
* Euler angles are much more restricted and exhibit singularities.
*
* For efficiency, if the target orientation is expressed w.r.t. to a fixed frame (relative to the planning frame),
* some stuff is precomputed. However, mobile reference frames are supported as well.
*
* The type value will return ORIENTATION_CONSTRAINT.
*
*/
class OrientationConstraint : public KinematicConstraint
Expand Down Expand Up @@ -440,6 +447,19 @@ class OrientationConstraint : public KinematicConstraint
*
* The returned matrix is always a valid rotation matrix.
*/
const Eigen::Matrix3d& getDesiredRotationMatrixInRefFrame() const
{
// validity of the rotation matrix is enforced in configure()
return desired_R_in_frame_id_;
}

/**
* \brief The rotation target in the reference or tf frame.
*
* @return The target rotation.
*
* The returned matrix is always a valid rotation matrix.
*/
const Eigen::Matrix3d& getDesiredRotationMatrix() const
{
// validity of the rotation matrix is enforced in configure()
Expand Down Expand Up @@ -485,16 +505,15 @@ class OrientationConstraint : public KinematicConstraint
}

protected:
const moveit::core::LinkModel* link_model_; /**< \brief The target link model */
Eigen::Matrix3d desired_rotation_matrix_; /**< \brief The desired rotation matrix in the tf frame. Guaranteed to
* be valid rotation matrix. */
Eigen::Matrix3d desired_rotation_matrix_inv_; /**< \brief The inverse of the desired rotation matrix, precomputed for
* efficiency. Guaranteed to be valid rotation matrix. */
std::string desired_rotation_frame_id_; /**< \brief The target frame of the transform tree */
bool mobile_frame_; /**< \brief Whether or not the header frame is mobile or fixed */
int parameterization_type_; /**< \brief Parameterization type for orientation tolerance. */
const moveit::core::LinkModel* link_model_; /**< The target link model */
Eigen::Matrix3d desired_R_in_frame_id_; /**< Desired rotation matrix in frame_id */
Eigen::Matrix3d desired_rotation_matrix_; /**< The desired rotation matrix in the tf frame */
Eigen::Matrix3d desired_rotation_matrix_inv_; /**< The inverse of desired_rotation_matrix_ (for efficiency) */
std::string desired_rotation_frame_id_; /**< The target frame of the transform tree */
bool mobile_frame_; /**< Whether or not the header frame is mobile or fixed */
int parameterization_type_; /**< Parameterization type for orientation tolerance */
double absolute_x_axis_tolerance_, absolute_y_axis_tolerance_,
absolute_z_axis_tolerance_; /**< \brief Storage for the tolerances */
absolute_z_axis_tolerance_; /**< Storage for the tolerances */
};

MOVEIT_CLASS_FORWARD(PositionConstraint); // Defines PositionConstraintPtr, ConstPtr, WeakPtr... etc
Expand Down
12 changes: 6 additions & 6 deletions moveit_core/kinematic_constraints/src/kinematic_constraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -555,10 +555,11 @@ bool OrientationConstraint::configure(const moveit_msgs::OrientationConstraint&
// clearing out any old data
clear();

link_model_ = robot_model_->getLinkModel(oc.link_name);
bool found;
link_model_ = robot_model_->getLinkModel(oc.link_name, &found);
if (!link_model_)
{
ROS_WARN_NAMED("kinematic_constraints", "Could not find link model for link name %s", oc.link_name.c_str());
ROS_WARN_NAMED("kinematic_constraints", "Could not find link model for link name '%s'", oc.link_name.c_str());
return false;
}
Eigen::Quaterniond q;
Expand All @@ -576,6 +577,7 @@ bool OrientationConstraint::configure(const moveit_msgs::OrientationConstraint&
ROS_WARN_NAMED("kinematic_constraints", "No frame specified for position constraint on link '%s'!",
oc.link_name.c_str());

desired_R_in_frame_id_ = Eigen::Quaterniond(q); // desired rotation wrt. frame_id
if (tf.isFixedFrame(oc.header.frame_id))
{
tf.transformQuaternion(oc.header.frame_id, q, q);
Expand Down Expand Up @@ -709,10 +711,8 @@ ConstraintEvaluationResult OrientationConstraint::decide(const moveit::core::Rob
else if (parameterization_type_ == moveit_msgs::OrientationConstraint::ROTATION_VECTOR)
{
Eigen::AngleAxisd aa(diff.linear());
xyz_rotation = aa.axis() * aa.angle();
xyz_rotation(0) = fabs(xyz_rotation(0));
xyz_rotation(1) = fabs(xyz_rotation(1));
xyz_rotation(2) = fabs(xyz_rotation(2));
// transform rotation vector from target frame to frame_id and take absolute values
xyz_rotation = (desired_R_in_frame_id_ * (aa.axis() * aa.angle())).cwiseAbs();
}
else
{
Expand Down
9 changes: 9 additions & 0 deletions moveit_core/kinematic_constraints/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,6 +183,7 @@ moveit_msgs::Constraints constructGoalConstraints(const std::string& link_name,

goal.orientation_constraints.resize(1);
moveit_msgs::OrientationConstraint& ocm = goal.orientation_constraints[0];
ocm.parameterization = moveit_msgs::OrientationConstraint::ROTATION_VECTOR;
ocm.link_name = link_name;
ocm.header = pose.header;
ocm.orientation = pose.pose.orientation;
Expand Down Expand Up @@ -565,9 +566,17 @@ bool resolveConstraintFrames(const moveit::core::RobotState& state, moveit_msgs:
// the constraint needs to be expressed in the frame of a robot link.
if (c.link_name != robot_link->getName())
{
if (c.parameterization == moveit_msgs::OrientationConstraint::XYZ_EULER_ANGLES)
{
ROS_ERROR_NAMED(
LOGNAME, "Euler angles parameterization is not supported for non-link frames in orientation constraints. \n"
"Switch to rotation vector parameterization.");
return false;
}
c.link_name = robot_link->getName();
Eigen::Quaterniond link_name_to_robot_link(transform.linear().transpose() *
state.getGlobalLinkTransform(robot_link).linear());
// adapt goal orientation
Eigen::Quaterniond quat_target;
tf2::fromMsg(c.orientation, quat_target);
c.orientation = tf2::toMsg(quat_target * link_name_to_robot_link);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -450,7 +450,7 @@ TEST_F(FloatingJointRobot, OrientationConstraintsParameterization)
EXPECT_TRUE(oc_rotvec.decide(robot_state).satisfied);
}

// and now some simple test cases where whe change the nominal orientation of the constraints,
// and now some simple test cases where we change the nominal orientation of the constraints,
// instead of changing the orientation of the robot
robot_state.setToDefaultValues();
robot_state.update();
Expand All @@ -474,6 +474,42 @@ TEST_F(FloatingJointRobot, OrientationConstraintsParameterization)
EXPECT_FALSE(oc_rotvec.decide(robot_state).satisfied);
}

TEST_F(FloatingJointRobot, ToleranceInRefFrame)
{
moveit::core::RobotState robot_state(robot_model_);
robot_state.setToDefaultValues();
auto base = rotation_vector_to_quat(M_PI / 2.0, 0, 0); // base rotation: 90° about x
setRobotEndEffectorOrientation(robot_state, base);
robot_state.update();

moveit::core::Transforms tf(robot_model_->getModelFrame());

// create message to configure orientation constraints
moveit_msgs::OrientationConstraint ocm;
ocm.link_name = "ee";
ocm.header.frame_id = robot_model_->getModelFrame();
ocm.parameterization = moveit_msgs::OrientationConstraint::ROTATION_VECTOR;
ocm.orientation = tf2::toMsg(base);
ocm.absolute_x_axis_tolerance = 0.2;
ocm.absolute_y_axis_tolerance = 0.2;
ocm.absolute_z_axis_tolerance = 1.0;
ocm.weight = 1.0;

kinematic_constraints::OrientationConstraint oc(robot_model_);
EXPECT_TRUE(oc.configure(ocm, tf));

EXPECT_TRUE(oc.decide(robot_state).satisfied); // link and target are perfectly aligned

// strong rotation w.r.t. base frame is ok
auto delta = rotation_vector_to_quat(0.1, 0.1, 0.9);
setRobotEndEffectorOrientation(robot_state, delta * base);
EXPECT_TRUE(oc.decide(robot_state).satisfied);

// strong rotation w.r.t. link frame is not ok
setRobotEndEffectorOrientation(robot_state, base * delta);
EXPECT_FALSE(oc.decide(robot_state).satisfied); // link and target are perfectly aligned
}

int main(int argc, char** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down

0 comments on commit 0a93db3

Please sign in to comment.