Skip to content

Commit

Permalink
Drop Melodic support (moveit#3677)
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke authored Dec 21, 2024
1 parent ce61fac commit e4a43d1
Show file tree
Hide file tree
Showing 10 changed files with 14 additions and 69 deletions.
4 changes: 2 additions & 2 deletions .github/ISSUE_TEMPLATE/bug_report.md
Original file line number Diff line number Diff line change
Expand Up @@ -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?
Expand Down
2 changes: 0 additions & 2 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
7 changes: 3 additions & 4 deletions .github/workflows/docker.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -101,7 +101,6 @@ jobs:
cache-to: type=inline
tags: |
${{ env.IMAGE }}
${{ matrix.IMAGE == 'master' && 'moveit/moveit:master-ci-testing' || '' }}
ci-testing:
needs: ci
Expand Down Expand Up @@ -154,7 +153,7 @@ jobs:
strategy:
fail-fast: false
matrix:
IMAGE: [noetic, master]
IMAGE: [noetic]
runs-on: ubuntu-latest
permissions:
packages: write
Expand Down
3 changes: 1 addition & 2 deletions moveit_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,7 @@
<test_depend>moveit_resources_panda_moveit_config</test_depend>
<test_depend>moveit_resources_pr2_description</test_depend>
<test_depend>tf2_kdl</test_depend>
<test_depend condition="$ROS_DISTRO == melodic">orocos_kdl</test_depend>
<test_depend condition="$ROS_DISTRO != melodic">liborocos-kdl-dev</test_depend>
<test_depend>liborocos-kdl-dev</test_depend>
<test_depend>rosunit</test_depend>
<test_depend>rostest</test_depend>
<test_depend>benchmark</test_depend>
Expand Down
30 changes: 5 additions & 25 deletions moveit_core/robot_state/test/test_cartesian_interpolator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
Expand All @@ -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<RobotState>(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<std::shared_ptr<RobotState>>& result, const Eigen::Vector3d& translation,
bool global)
{
Expand All @@ -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<std::shared_ptr<RobotState>> result_;
};
#ifndef _OLD_GTEST
RobotModelPtr PandaRobot::robot_model_;
JointModelGroup* PandaRobot::jmg_ = nullptr;
const LinkModel* PandaRobot::link_ = nullptr;
#endif

TEST_F(PandaRobot, testVectorGlobal)
{
Expand Down
3 changes: 1 addition & 2 deletions moveit_kinematics/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,7 @@
<depend>eigen</depend>
<depend>tf2</depend>
<depend>tf2_kdl</depend>
<depend condition="$ROS_DISTRO == melodic">orocos_kdl</depend>
<depend condition="$ROS_DISTRO != melodic">liborocos-kdl-dev</depend>
<depend>liborocos-kdl-dev</depend>

<!-- some requirements of ikfast scripts -->
<exec_depend>liburdfdom-tools</exec_depend> <!-- provides check_urdf -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,15 +55,8 @@
#include <ompl/tools/config/SelfConfig.h>
#include <ompl/base/spaces/SE3StateSpace.h>
#include <ompl/datastructures/PDF.h>
// TODO: remove when ROS Melodic and older are no longer supported
#if OMPL_VERSION_VALUE < 1005000
#include <ompl/base/PlannerTerminationCondition.h>
#else
// IterationTerminationCondition was moved to a separate file and
// CostConvergenceTerminationCondition was added in OMPL 1.5.0.
#include <ompl/base/terminationconditions/IterationTerminationCondition.h>
#include <ompl/base/terminationconditions/CostConvergenceTerminationCondition.h>
#endif

#include "ompl/base/objectives/PathLengthOptimizationObjective.h"
#include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"
Expand Down Expand Up @@ -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")
Expand All @@ -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.
Expand Down Expand Up @@ -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
Expand All @@ -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());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,12 +69,9 @@
#include <ompl/geometric/planners/prm/LazyPRMstar.h>
#include <ompl/geometric/planners/prm/SPARS.h>
#include <ompl/geometric/planners/prm/SPARStwo.h>
// TODO: remove when ROS Melodic and older are no longer supported
#if OMPL_VERSION_VALUE >= 1005000
#include <ompl/geometric/planners/informedtrees/AITstar.h>
#include <ompl/geometric/planners/informedtrees/ABITstar.h>
#include <ompl/geometric/planners/informedtrees/BITstar.h>
#endif

#include <moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h>
#include <moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h>
Expand Down Expand Up @@ -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 <>
Expand Down Expand Up @@ -230,7 +225,6 @@ MultiQueryPlannerAllocator::allocatePersistentPlanner<ompl::geometric::LazyPRMst
return new og::LazyPRMstar(data);
};
} // namespace ompl_interface
#endif

ompl_interface::PlanningContextManager::PlanningContextManager(moveit::core::RobotModelConstPtr robot_model,
constraint_samplers::ConstraintSamplerManagerPtr csm)
Expand Down Expand Up @@ -299,12 +293,9 @@ void ompl_interface::PlanningContextManager::registerDefaultPlanners()
registerPlannerAllocatorHelper<og::SPARStwo>("geometric::SPARStwo");
registerPlannerAllocatorHelper<og::STRIDE>("geometric::STRIDE");
registerPlannerAllocatorHelper<og::TRRT>("geometric::TRRT");
// TODO: remove when ROS Melodic and older are no longer supported
#if OMPL_VERSION_VALUE >= 1005000
registerPlannerAllocatorHelper<og::AITstar>("geometric::AITstar");
registerPlannerAllocatorHelper<og::ABITstar>("geometric::ABITstar");
registerPlannerAllocatorHelper<og::BITstar>("geometric::BITstar");
#endif
}

void ompl_interface::PlanningContextManager::registerDefaultStateSpaces()
Expand Down
3 changes: 1 addition & 2 deletions moveit_planners/pilz_industrial_motion_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@
<depend>moveit_core</depend>
<depend>moveit_ros_planning</depend> <!-- RobotModelLoader -->
<depend>moveit_ros_move_group</depend> <!-- move_group capability -->
<depend condition="$ROS_DISTRO == melodic">orocos_kdl</depend>
<depend condition="$ROS_DISTRO != melodic">liborocos-kdl-dev</depend>
<depend>liborocos-kdl-dev</depend>
<depend>pluginlib</depend>
<depend>roscpp</depend>
<depend>tf2</depend>
Expand Down
9 changes: 1 addition & 8 deletions moveit_setup_assistant/src/tools/moveit_config_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -661,14 +661,10 @@ std::vector<OMPLPlannerDescription> 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");
Expand Down Expand Up @@ -876,8 +872,6 @@ std::vector<OMPLPlannerDescription> 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");
Expand Down Expand Up @@ -947,7 +941,6 @@ std::vector<OMPLPlannerDescription> 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;
}
Expand Down

0 comments on commit e4a43d1

Please sign in to comment.