Skip to content

Commit ce78cc4

Browse files
rr-tom-noblesjahr
andauthored
Fixes pilz tests (#3095)
Co-authored-by: Sebastian Jahr <[email protected]>
1 parent 1944811 commit ce78cc4

File tree

1 file changed

+6
-5
lines changed

1 file changed

+6
-5
lines changed

moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -415,9 +415,10 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentityColl
415415
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
416416
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
417417

418-
// Attach an object with no subframes, and no transform
418+
// Attach an object with ignored subframes, and no transform
419419
Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
420-
attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
420+
moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
421+
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
421422

422423
// The RobotState should be able to use an object pose to set the joints
423424
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
@@ -440,12 +441,12 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedC
440441
const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
441442
Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
442443

443-
// Attach an object with no subframes, and a non-trivial transform
444+
// Attach an object with ignored subframes, and a non-trivial transform
444445
Eigen::Isometry3d object_pose_in_tip;
445446
object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
446447
object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());
447-
448-
attachToLink(state, tip_link, "object", object_pose_in_tip, { {} });
448+
moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
449+
attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
449450

450451
// The RobotState should be able to use an object pose to set the joints
451452
Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;

0 commit comments

Comments
 (0)