From e4a43d18e6f1a8a012bdf8b85f2e1a9cfe9f80b8 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 21 Dec 2024 21:44:11 +0000 Subject: [PATCH] Drop Melodic support (#3677) --- .github/ISSUE_TEMPLATE/bug_report.md | 4 +-- .github/workflows/ci.yaml | 2 -- .github/workflows/docker.yaml | 7 ++--- moveit_core/package.xml | 3 +- .../test/test_cartesian_interpolator.cpp | 30 ++++--------------- moveit_kinematics/package.xml | 3 +- .../src/model_based_planning_context.cpp | 13 -------- .../src/planning_context_manager.cpp | 9 ------ .../package.xml | 3 +- .../src/tools/moveit_config_data.cpp | 9 +----- 10 files changed, 14 insertions(+), 69 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index 6806c4801e..80d77106a6 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -12,8 +12,8 @@ assignees: '' Overview of your issue here. ### Your environment -* ROS Distro: [Kinetic|Melodic|Noetic] -* OS Version: e.g. Ubuntu 18.04 +* ROS Distro: [Noetic|One] +* OS Version: e.g. Ubuntu 20.04 * Source or Binary build? * If binary, which release version? * If source, which branch? diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index c2e4413eb0..6d2fd411db 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -30,8 +30,6 @@ jobs: IKFAST_TEST: true CATKIN_LINT: true CLANG_TIDY: pedantic - - IMAGE: master-ci # ROS Melodic with all dependencies required for master - CATKIN_LINT: true - IMAGE: jammy-ci - IMAGE: noble-ci env: diff --git a/.github/workflows/docker.yaml b/.github/workflows/docker.yaml index d4afb59d83..74241e409b 100644 --- a/.github/workflows/docker.yaml +++ b/.github/workflows/docker.yaml @@ -61,14 +61,14 @@ jobs: strategy: fail-fast: false matrix: - IMAGE: [noetic, master] + IMAGE: [noetic] runs-on: ubuntu-latest permissions: packages: write contents: read env: IMAGE: moveit/moveit:${{ matrix.IMAGE }}-${{ github.job }} - ROS_DISTRO: ${{ matrix.IMAGE == 'master' && 'melodic' || 'noetic' }} + ROS_DISTRO: ${{ matrix.IMAGE }} steps: - uses: rhaschke/docker-run-action@v5 @@ -101,7 +101,6 @@ jobs: cache-to: type=inline tags: | ${{ env.IMAGE }} - ${{ matrix.IMAGE == 'master' && 'moveit/moveit:master-ci-testing' || '' }} ci-testing: needs: ci @@ -154,7 +153,7 @@ jobs: strategy: fail-fast: false matrix: - IMAGE: [noetic, master] + IMAGE: [noetic] runs-on: ubuntu-latest permissions: packages: write diff --git a/moveit_core/package.xml b/moveit_core/package.xml index 497f9cd656..651b6a5ca1 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -62,8 +62,7 @@ moveit_resources_panda_moveit_config moveit_resources_pr2_description tf2_kdl - orocos_kdl - liborocos-kdl-dev + liborocos-kdl-dev rosunit rostest benchmark diff --git a/moveit_core/robot_state/test/test_cartesian_interpolator.cpp b/moveit_core/robot_state/test/test_cartesian_interpolator.cpp index 8f876aff3c..9d8bf5cb3e 100644 --- a/moveit_core/robot_state/test/test_cartesian_interpolator.cpp +++ b/moveit_core/robot_state/test/test_cartesian_interpolator.cpp @@ -200,18 +200,10 @@ TEST_F(SimpleRobot, checkRelativeJointSpaceJump) EXPECT_NEAR(1.0, fraction, 0.01); } -// Gracefully handle gtest 1.8 (Melodic) -#ifndef INSTANTIATE_TEST_SUITE_P -#define _STATIC -#define _OLD_GTEST -#else -#define _STATIC static -#endif - class PandaRobot : public testing::Test { protected: - _STATIC void SetUpTestSuite() // setup resources shared between tests + static void SetUpTestSuite() // setup resources shared between tests { robot_model_ = loadTestingRobotModel("panda"); jmg_ = robot_model_->getJointModelGroup("panda_arm"); @@ -220,28 +212,18 @@ class PandaRobot : public testing::Test loadIKPluginForGroup(jmg_, "panda_link0", link_->getName()); } - _STATIC void TearDownTestSuite() + static void TearDownTestSuite() { robot_model_.reset(); } void SetUp() override { -#ifdef _OLD_GTEST - SetUpTestSuite(); -#endif start_state_ = std::make_shared(robot_model_); ASSERT_TRUE(start_state_->setToDefaultValues(jmg_, "ready")); start_pose_ = start_state_->getGlobalLinkTransform(link_); } -#ifdef _OLD_GTEST - void TearDown() override - { - TearDownTestSuite(); - } -#endif - double computeCartesianPath(std::vector>& result, const Eigen::Vector3d& translation, bool global) { @@ -260,20 +242,18 @@ class PandaRobot : public testing::Test } protected: - _STATIC RobotModelPtr robot_model_; - _STATIC JointModelGroup* jmg_; - _STATIC const LinkModel* link_; + static RobotModelPtr robot_model_; + static JointModelGroup* jmg_; + static const LinkModel* link_; double prec_ = 1e-8; RobotStatePtr start_state_; Eigen::Isometry3d start_pose_; std::vector> result_; }; -#ifndef _OLD_GTEST RobotModelPtr PandaRobot::robot_model_; JointModelGroup* PandaRobot::jmg_ = nullptr; const LinkModel* PandaRobot::link_ = nullptr; -#endif TEST_F(PandaRobot, testVectorGlobal) { diff --git a/moveit_kinematics/package.xml b/moveit_kinematics/package.xml index 4b63b4f4ad..7072111cf9 100644 --- a/moveit_kinematics/package.xml +++ b/moveit_kinematics/package.xml @@ -27,8 +27,7 @@ eigen tf2 tf2_kdl - orocos_kdl - liborocos-kdl-dev + liborocos-kdl-dev liburdfdom-tools diff --git a/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp b/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp index b1ca6a2ddc..2e3b0d03ec 100644 --- a/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp +++ b/moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp @@ -55,15 +55,8 @@ #include #include #include -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE < 1005000 -#include -#else -// IterationTerminationCondition was moved to a separate file and -// CostConvergenceTerminationCondition was added in OMPL 1.5.0. #include #include -#endif #include "ompl/base/objectives/PathLengthOptimizationObjective.h" #include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h" @@ -516,8 +509,6 @@ ompl_interface::ModelBasedPlanningContext::constructPlannerTerminationCondition( else ROS_ERROR_NAMED(LOGNAME, "Missing argument to Iteration termination condition"); } -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 // Terminate if the cost has converged or a timeout occurs. // Only useful for anytime/optimizing planners. else if (termination_and_params[0] == "CostConvergence") @@ -534,7 +525,6 @@ ompl_interface::ModelBasedPlanningContext::constructPlannerTerminationCondition( ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)), ob::CostConvergenceTerminationCondition(ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon)); } -#endif // Terminate as soon as an exact solution is found or a timeout occurs. // This modifies the behavior of anytime/optimizing planners to terminate upon discovering // the first feasible solution. @@ -562,8 +552,6 @@ void ompl_interface::ModelBasedPlanningContext::clear() { if (!multi_query_planning_enabled_) ompl_simple_setup_->clear(); -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 else { // For LazyPRM and LazyPRMstar we assume that the environment *could* have changed @@ -574,7 +562,6 @@ void ompl_interface::ModelBasedPlanningContext::clear() if (planner != nullptr) planner->clearValidity(); } -#endif ompl_simple_setup_->clearStartStates(); ompl_simple_setup_->setGoal(ob::GoalPtr()); ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr()); diff --git a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp index 74e472bd22..9a10200085 100644 --- a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp @@ -69,12 +69,9 @@ #include #include #include -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 #include #include #include -#endif #include #include @@ -200,9 +197,7 @@ ompl_interface::MultiQueryPlannerAllocator::allocatePersistentPlanner(const ob:: { return nullptr; }; -// TODO: remove when ROS Melodic and older are no longer supported // namespace is scoped instead of global because of GCC bug 56480 -#if OMPL_VERSION_VALUE >= 1005000 namespace ompl_interface { template <> @@ -230,7 +225,6 @@ MultiQueryPlannerAllocator::allocatePersistentPlanner("geometric::SPARStwo"); registerPlannerAllocatorHelper("geometric::STRIDE"); registerPlannerAllocatorHelper("geometric::TRRT"); -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 registerPlannerAllocatorHelper("geometric::AITstar"); registerPlannerAllocatorHelper("geometric::ABITstar"); registerPlannerAllocatorHelper("geometric::BITstar"); -#endif } void ompl_interface::PlanningContextManager::registerDefaultStateSpaces() diff --git a/moveit_planners/pilz_industrial_motion_planner/package.xml b/moveit_planners/pilz_industrial_motion_planner/package.xml index 0961ae0ba2..b188daa4e5 100644 --- a/moveit_planners/pilz_industrial_motion_planner/package.xml +++ b/moveit_planners/pilz_industrial_motion_planner/package.xml @@ -24,8 +24,7 @@ moveit_core moveit_ros_planning moveit_ros_move_group - orocos_kdl - liborocos-kdl-dev + liborocos-kdl-dev pluginlib roscpp tf2 diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index f1ffda4c4b..6381eff7b9 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -661,14 +661,10 @@ std::vector MoveItConfigData::getOMPLPlanners() const aps.addParameter("hybridize", "true", "Compute hybrid solution trajectories"); aps.addParameter("max_hybrid_paths", "24", "Number of hybrid paths generated per iteration"); aps.addParameter("num_planners", "4", "The number of default planners to use for planning"); -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 - // This parameter was added in OMPL 1.5.0 - aps.addParameter("planners", "", + aps.addParameter("planners", "", // added in OMPL 1.5.0 "A comma-separated list of planner types (e.g., \"PRM,EST,RRTConnect\"" "Optionally, planner parameters can be passed to change the default:" "\"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]\""); -#endif planner_des.push_back(aps); OMPLPlannerDescription sbl("SBL", "geometric"); @@ -876,8 +872,6 @@ std::vector MoveItConfigData::getOMPLPlanners() const spar_stwo.addParameter("max_failures", "5000", "maximum consecutive failure limit. default: 5000"); planner_des.push_back(spar_stwo); -// TODO: remove when ROS Melodic and older are no longer supported -#if OMPL_VERSION_VALUE >= 1005000 OMPLPlannerDescription aitstar("AITstar", "geometric"); aitstar.addParameter("use_k_nearest", "1", "whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1"); @@ -947,7 +941,6 @@ std::vector MoveItConfigData::getOMPLPlanners() const "sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0"); bitstar.addParameter("find_approximate_solutions", "0", "track approximate solutions (1) or not (0). Default: 0"); planner_des.push_back(bitstar); -#endif return planner_des; }