diff --git a/.docker/ci/Dockerfile b/.docker/ci/Dockerfile index 827bae17d9..2492da642f 100644 --- a/.docker/ci/Dockerfile +++ b/.docker/ci/Dockerfile @@ -18,7 +18,7 @@ COPY . src/moveit2 RUN \ # Update apt package list as previous containers clear the cache apt-get -q update && \ - apt-get -q -y upgrade --with-new-pkgs && \ + apt-get -q -y upgrade && \ # # Install some base dependencies apt-get -q install --no-install-recommends -y \ diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index fd1dc1a4c6..5ac8d6b4f8 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -26,10 +26,10 @@ jobs: CLANG_TIDY: pedantic - IMAGE: humble-ci ROS_DISTRO: humble - - IMAGE: humble-ci-testing - ROS_DISTRO: humble - IMAGE: jazzy-ci ROS_DISTRO: jazzy + - IMAGE: jazzy-ci-testing + ROS_DISTRO: jazzy env: # TODO(andyz): When this clang-tidy issue is fixed, remove -Wno-unknown-warning-option # https://stackoverflow.com/a/41673702 diff --git a/moveit2_humble.repos b/moveit2_humble.repos deleted file mode 100644 index 71a9316f22..0000000000 --- a/moveit2_humble.repos +++ /dev/null @@ -1,5 +0,0 @@ -repositories: - generate_parameter_library: - type: git - url: https://github.com/PickNikRobotics/generate_parameter_library.git - version: 0.3.7 diff --git a/moveit2_iron.repos b/moveit2_iron.repos deleted file mode 100644 index 71a9316f22..0000000000 --- a/moveit2_iron.repos +++ /dev/null @@ -1,5 +0,0 @@ -repositories: - generate_parameter_library: - type: git - url: https://github.com/PickNikRobotics/generate_parameter_library.git - version: 0.3.7 diff --git a/moveit_core/robot_state/test/robot_state_test.cpp b/moveit_core/robot_state/test/robot_state_test.cpp index bea2b7e229..e1d710805c 100644 --- a/moveit_core/robot_state/test/robot_state_test.cpp +++ b/moveit_core/robot_state/test/robot_state_test.cpp @@ -781,6 +781,8 @@ TEST_F(OneRobot, rigidlyConnectedParent) EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_b), link_a); moveit::core::RobotState state(robot_model_); + state.setToDefaultValues(); + state.updateLinkTransforms(); EXPECT_EQ(state.getRigidlyConnectedParentLinkModel("link_b"), link_a); diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp index a0383aaa24..66cee20108 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_trajectory_functions.cpp @@ -415,9 +415,10 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentityColl const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_); Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_); - // Attach an object with no subframes, and no transform + // Attach an object with ignored subframes, and no transform Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity(); - attachToLink(state, tip_link, "object", object_pose_in_tip, { {} }); + moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } }); + attachToLink(state, tip_link, "object", object_pose_in_tip, subframes); // The RobotState should be able to use an object pose to set the joints Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip; @@ -440,12 +441,12 @@ TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedC const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_); Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_); - // Attach an object with no subframes, and a non-trivial transform + // Attach an object with ignored subframes, and a non-trivial transform Eigen::Isometry3d object_pose_in_tip; object_pose_in_tip = Eigen::Translation3d(1, 2, 3); object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX()); - - attachToLink(state, tip_link, "object", object_pose_in_tip, { {} }); + moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } }); + attachToLink(state, tip_link, "object", object_pose_in_tip, subframes); // The RobotState should be able to use an object pose to set the joints Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;