Skip to content

Commit 59e68d9

Browse files
authored
Merge branch 'moveit:main' into patch-3
2 parents c7fd9a7 + 2490e51 commit 59e68d9

File tree

39 files changed

+496
-303
lines changed

39 files changed

+496
-303
lines changed

.docker/release/Dockerfile

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,9 @@ ARG ROS_DISTRO=rolling
55
FROM ros:${ROS_DISTRO}-ros-base
66
LABEL maintainer Robert Haschke [email protected]
77

8+
# Allow non-interactive installation of ros-*-rmw-connextdds
9+
ENV RTI_NC_LICENSE_ACCEPTED yes
10+
811
# Commands are combined in single RUN statement with "apt/lists" folder removal to reduce image size
912
RUN apt-get update -q && \
1013
apt-get upgrade -q -y && \

.github/workflows/tutorial_docker.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@ jobs:
1616
strategy:
1717
fail-fast: false
1818
matrix:
19-
ROS_DISTRO: [rolling, humble, iron, jazzy]
19+
ROS_DISTRO: [rolling, jazzy]
2020
runs-on: ubuntu-latest
2121
permissions:
2222
packages: write

moveit_configs_utils/moveit_configs_utils/launches.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -249,7 +249,7 @@ def generate_move_group_launch(moveit_config):
249249
parameters=move_group_params,
250250
extra_debug_args=["--debug"],
251251
# Set the display variable, in case OpenGL code is used internally
252-
additional_env={"DISPLAY": os.environ["DISPLAY"]},
252+
additional_env={"DISPLAY": os.environ.get("DISPLAY", "")},
253253
)
254254
return ld
255255

moveit_core/constraint_samplers/src/default_constraint_samplers.cpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -515,21 +515,20 @@ bool IKConstraintSampler::samplePose(Eigen::Vector3d& pos, Eigen::Quaterniond& q
515515
moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
516516
{
517517
Eigen::Vector3d rotation_vector(angle_x, angle_y, angle_z);
518+
// convert rotation vector from frame_id to target frame
519+
rotation_vector =
520+
sampling_pose_.orientation_constraint_->getDesiredRotationMatrixInRefFrame().transpose() * rotation_vector;
518521
diff = Eigen::Isometry3d(Eigen::AngleAxisd(rotation_vector.norm(), rotation_vector.normalized()));
519522
}
520523
else
521524
{
522525
/* The parameterization type should be validated in configure, so this should never happen. */
523526
RCLCPP_ERROR(getLogger(), "The parameterization type for the orientation constraints is invalid.");
524527
}
525-
// diff is isometry by construction
526-
// getDesiredRotationMatrix() returns a valid rotation matrix by contract
527-
// reqr has thus to be a valid isometry
528-
Eigen::Isometry3d reqr(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());
529-
quat = Eigen::Quaterniond(reqr.linear()); // reqr is isometry, so quat has to be normalized
530528

531-
// if this constraint is with respect a mobile frame, we need to convert this rotation to the root frame of the
532-
// model
529+
quat = Eigen::Quaterniond(sampling_pose_.orientation_constraint_->getDesiredRotationMatrix() * diff.linear());
530+
531+
// if this constraint is with respect to a mobile frame, we need to convert this rotation to the root frame of the model
533532
if (sampling_pose_.orientation_constraint_->mobileReferenceFrame())
534533
{
535534
// getFrameTransform() returns a valid isometry by contract

moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h

Lines changed: 34 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -336,12 +336,19 @@ MOVEIT_CLASS_FORWARD(OrientationConstraint); // Defines OrientationConstraintPt
336336
/**
337337
* \brief Class for constraints on the orientation of a link
338338
*
339-
* This class expresses an orientation constraint on a particular
340-
* link. The constraint is specified in terms of a quaternion, with
341-
* tolerances on X,Y, and Z axes. The rotation difference is computed
342-
* based on the XYZ Euler angle formulation (intrinsic rotations) or as a rotation vector. This depends on the
343-
* `Parameterization` type. The header on the quaternion can be specified in terms of either a fixed or a mobile
344-
* frame. The type value will return ORIENTATION_CONSTRAINT.
339+
* This class expresses an orientation constraint on a particular link.
340+
* The constraint specifies a target orientation via a quaternion as well as
341+
* tolerances on X,Y, and Z rotation axes.
342+
* The rotation difference between the target and actual link orientation is expressed
343+
* either as XYZ Euler angles or as a rotation vector (depending on the `parameterization` type).
344+
* The latter is highly recommended, because it supports resolution of subframes and attached bodies.
345+
* Also, rotation vector representation allows to interpret the tolerances always w.r.t. the given reference frame.
346+
* Euler angles are much more restricted and exhibit singularities.
347+
*
348+
* For efficiency, if the target orientation is expressed w.r.t. to a fixed frame (relative to the planning frame),
349+
* some stuff is precomputed. However, mobile reference frames are supported as well.
350+
*
351+
* The type value will return ORIENTATION_CONSTRAINT.
345352
*
346353
*/
347354
class OrientationConstraint : public KinematicConstraint
@@ -439,6 +446,19 @@ class OrientationConstraint : public KinematicConstraint
439446
*
440447
* The returned matrix is always a valid rotation matrix.
441448
*/
449+
const Eigen::Matrix3d& getDesiredRotationMatrixInRefFrame() const
450+
{
451+
// validity of the rotation matrix is enforced in configure()
452+
return desired_R_in_frame_id_;
453+
}
454+
455+
/**
456+
* \brief The rotation target in the reference or tf frame.
457+
*
458+
* @return The target rotation.
459+
*
460+
* The returned matrix is always a valid rotation matrix.
461+
*/
442462
const Eigen::Matrix3d& getDesiredRotationMatrix() const
443463
{
444464
// validity of the rotation matrix is enforced in configure()
@@ -484,16 +504,15 @@ class OrientationConstraint : public KinematicConstraint
484504
}
485505

486506
protected:
487-
const moveit::core::LinkModel* link_model_; /**< \brief The target link model */
488-
Eigen::Matrix3d desired_rotation_matrix_; /**< \brief The desired rotation matrix in the tf frame. Guaranteed to
489-
* be valid rotation matrix. */
490-
Eigen::Matrix3d desired_rotation_matrix_inv_; /**< \brief The inverse of the desired rotation matrix, precomputed for
491-
* efficiency. Guaranteed to be valid rotation matrix. */
492-
std::string desired_rotation_frame_id_; /**< \brief The target frame of the transform tree */
493-
bool mobile_frame_; /**< \brief Whether or not the header frame is mobile or fixed */
494-
int parameterization_type_; /**< \brief Parameterization type for orientation tolerance. */
507+
const moveit::core::LinkModel* link_model_; /**< The target link model */
508+
Eigen::Matrix3d desired_R_in_frame_id_; /**< Desired rotation matrix in frame_id */
509+
Eigen::Matrix3d desired_rotation_matrix_; /**< The desired rotation matrix in the tf frame */
510+
Eigen::Matrix3d desired_rotation_matrix_inv_; /**< The inverse of desired_rotation_matrix_ (for efficiency) */
511+
std::string desired_rotation_frame_id_; /**< The target frame of the transform tree */
512+
bool mobile_frame_; /**< Whether or not the header frame is mobile or fixed */
513+
int parameterization_type_; /**< Parameterization type for orientation tolerance */
495514
double absolute_x_axis_tolerance_, absolute_y_axis_tolerance_,
496-
absolute_z_axis_tolerance_; /**< \brief Storage for the tolerances */
515+
absolute_z_axis_tolerance_; /**< Storage for the tolerances */
497516
};
498517

499518
MOVEIT_CLASS_FORWARD(PositionConstraint); // Defines PositionConstraintPtr, ConstPtr, WeakPtr... etc

moveit_core/kinematic_constraints/src/kinematic_constraint.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -597,7 +597,8 @@ bool OrientationConstraint::configure(const moveit_msgs::msg::OrientationConstra
597597
// clearing out any old data
598598
clear();
599599

600-
link_model_ = robot_model_->getLinkModel(oc.link_name);
600+
bool found; // just needed to silent the error message in getLinkModel()
601+
link_model_ = robot_model_->getLinkModel(oc.link_name, &found);
601602
if (!link_model_)
602603
{
603604
RCLCPP_WARN(getLogger(), "Could not find link model for link name %s", oc.link_name.c_str());
@@ -617,6 +618,7 @@ bool OrientationConstraint::configure(const moveit_msgs::msg::OrientationConstra
617618
if (oc.header.frame_id.empty())
618619
RCLCPP_WARN(getLogger(), "No frame specified for position constraint on link '%s'!", oc.link_name.c_str());
619620

621+
desired_R_in_frame_id_ = Eigen::Quaterniond(q); // desired rotation wrt. frame_id
620622
if (tf.isFixedFrame(oc.header.frame_id))
621623
{
622624
tf.transformQuaternion(oc.header.frame_id, q, q);
@@ -749,10 +751,8 @@ ConstraintEvaluationResult OrientationConstraint::decide(const moveit::core::Rob
749751
else if (parameterization_type_ == moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR)
750752
{
751753
Eigen::AngleAxisd aa(diff.linear());
752-
xyz_rotation = aa.axis() * aa.angle();
753-
xyz_rotation(0) = fabs(xyz_rotation(0));
754-
xyz_rotation(1) = fabs(xyz_rotation(1));
755-
xyz_rotation(2) = fabs(xyz_rotation(2));
754+
// transform rotation vector from target frame to frame_id and take absolute values
755+
xyz_rotation = (desired_R_in_frame_id_ * (aa.axis() * aa.angle())).cwiseAbs();
756756
}
757757
else
758758
{

moveit_core/kinematic_constraints/src/utils.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -217,6 +217,7 @@ moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_n
217217

218218
goal.orientation_constraints.resize(1);
219219
moveit_msgs::msg::OrientationConstraint& ocm = goal.orientation_constraints[0];
220+
ocm.parameterization = moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR;
220221
ocm.link_name = link_name;
221222
ocm.header = pose.header;
222223
ocm.orientation = pose.pose.orientation;
@@ -655,9 +656,17 @@ bool resolveConstraintFrames(const moveit::core::RobotState& state, moveit_msgs:
655656
// the constraint needs to be expressed in the frame of a robot link.
656657
if (c.link_name != robot_link->getName())
657658
{
659+
if (c.parameterization == moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
660+
{
661+
RCLCPP_ERROR(getLogger(),
662+
"Euler angles parameterization is not supported for non-link frames in orientation constraints. \n"
663+
"Switch to rotation vector parameterization.");
664+
return false;
665+
}
658666
c.link_name = robot_link->getName();
659667
Eigen::Quaterniond link_name_to_robot_link(transform.linear().transpose() *
660668
state.getGlobalLinkTransform(robot_link).linear());
669+
// adapt goal orientation
661670
Eigen::Quaterniond quat_target;
662671
tf2::fromMsg(c.orientation, quat_target);
663672
c.orientation = tf2::toMsg(quat_target * link_name_to_robot_link);

moveit_core/kinematic_constraints/test/test_orientation_constraints.cpp

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -475,6 +475,42 @@ TEST_F(FloatingJointRobot, OrientationConstraintsParameterization)
475475
EXPECT_FALSE(oc_rotvec.decide(robot_state).satisfied);
476476
}
477477

478+
TEST_F(FloatingJointRobot, ToleranceInRefFrame)
479+
{
480+
moveit::core::RobotState robot_state(robot_model_);
481+
robot_state.setToDefaultValues();
482+
auto base = rotationVectorToQuaternion(M_PI / 2.0, 0, 0); // base rotation: 90° about x
483+
setRobotEndEffectorOrientation(robot_state, base);
484+
robot_state.update();
485+
486+
moveit::core::Transforms tf(robot_model_->getModelFrame());
487+
488+
// create message to configure orientation constraints
489+
moveit_msgs::msg::OrientationConstraint ocm;
490+
ocm.link_name = "ee";
491+
ocm.header.frame_id = robot_model_->getModelFrame();
492+
ocm.parameterization = moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR;
493+
ocm.orientation = tf2::toMsg(base);
494+
ocm.absolute_x_axis_tolerance = 0.2;
495+
ocm.absolute_y_axis_tolerance = 0.2;
496+
ocm.absolute_z_axis_tolerance = 1.0;
497+
ocm.weight = 1.0;
498+
499+
kinematic_constraints::OrientationConstraint oc(robot_model_);
500+
EXPECT_TRUE(oc.configure(ocm, tf));
501+
502+
EXPECT_TRUE(oc.decide(robot_state).satisfied); // link and target are perfectly aligned
503+
504+
// strong rotation w.r.t. base frame is ok
505+
auto delta = rotationVectorToQuaternion(0.1, 0.1, 0.9);
506+
setRobotEndEffectorOrientation(robot_state, delta * base);
507+
EXPECT_TRUE(oc.decide(robot_state).satisfied);
508+
509+
// strong rotation w.r.t. link frame is not ok
510+
setRobotEndEffectorOrientation(robot_state, base * delta);
511+
EXPECT_FALSE(oc.decide(robot_state).satisfied); // link and target are perfectly aligned
512+
}
513+
478514
int main(int argc, char** argv)
479515
{
480516
testing::InitGoogleTest(&argc, argv);

moveit_core/robot_model/include/moveit/robot_model/joint_model.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -514,10 +514,10 @@ class JointModel
514514
/** \brief The joint this one mimics (nullptr for joints that do not mimic) */
515515
const JointModel* mimic_;
516516

517-
/** \brief The offset to the mimic joint */
517+
/** \brief The multiplier to the mimic joint */
518518
double mimic_factor_;
519519

520-
/** \brief The multiplier to the mimic joint */
520+
/** \brief The offset to the mimic joint */
521521
double mimic_offset_;
522522

523523
/** \brief The set of joints that should get a value copied to them when this joint changes */

moveit_core/robot_state/src/robot_state.cpp

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1496,19 +1496,25 @@ bool RobotState::getJacobian(const JointModelGroup* group, const LinkModel* link
14961496
const int rows = use_quaternion_representation ? 7 : 6;
14971497
const int columns = group->getVariableCount();
14981498
jacobian.resize(rows, columns);
1499+
jacobian.setZero();
14991500

15001501
// Get the tip pose with respect to the group root link. Append the user-requested offset 'reference_point_position'.
15011502
const Eigen::Isometry3d root_pose_tip = root_pose_world * getGlobalLinkTransform(link);
15021503
const Eigen::Vector3d tip_point = root_pose_tip * reference_point_position;
15031504

1504-
// Here we iterate over all the group active joints, and compute how much each of them contribute to the Cartesian
1505-
// displacement at the tip. So we build the Jacobian incrementally joint by joint.
1506-
std::size_t active_joints = group->getActiveJointModels().size();
1505+
// Initialize the column index of the Jacobian matrix.
15071506
int i = 0;
1508-
for (std::size_t joint = 0; joint < active_joints; ++joint)
1507+
1508+
// Here we iterate over all the group active joints, and compute how much each of them contribute to the Cartesian
1509+
// displacement at the tip. So we build the Jacobian incrementally joint by joint up to the parent joint of the reference link.
1510+
for (const JointModel* joint_model : joint_models)
15091511
{
1512+
// Stop looping if we reached the child joint of the reference link.
1513+
if (joint_model->getParentLinkModel() == link)
1514+
{
1515+
break;
1516+
}
15101517
// Get the child link for the current joint, and its pose with respect to the group root link.
1511-
const JointModel* joint_model = joint_models[joint];
15121518
const LinkModel* child_link_model = joint_model->getChildLinkModel();
15131519
const Eigen::Isometry3d& root_pose_link = root_pose_world * getGlobalLinkTransform(child_link_model);
15141520

@@ -1540,6 +1546,7 @@ bool RobotState::getJacobian(const JointModelGroup* group, const LinkModel* link
15401546
RCLCPP_ERROR(getLogger(), "Unknown type of joint in Jacobian computation");
15411547
return false;
15421548
}
1549+
15431550
i += joint_model->getVariableCount();
15441551
}
15451552

0 commit comments

Comments
 (0)