mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
commit
93d95e394f
@ -1,6 +1,5 @@
|
||||
---
|
||||
Checks: '-*,
|
||||
performance-*,
|
||||
Checks: 'performance-*,
|
||||
llvm-namespace-comment,
|
||||
modernize-redundant-void-arg,
|
||||
modernize-use-nullptr,
|
||||
|
||||
60
.github/workflows/ci.yaml
vendored
Normal file
60
.github/workflows/ci.yaml
vendored
Normal file
@ -0,0 +1,60 @@
|
||||
# This config uses industrial_ci (https://github.com/ros-industrial/industrial_ci.git).
|
||||
# For troubleshooting, see readme (https://github.com/ros-industrial/industrial_ci/blob/master/README.rst)
|
||||
|
||||
name: CI
|
||||
|
||||
on:
|
||||
workflow_dispatch:
|
||||
pull_request:
|
||||
push:
|
||||
|
||||
jobs:
|
||||
default:
|
||||
strategy:
|
||||
matrix:
|
||||
env:
|
||||
- IMAGE: melodic-source
|
||||
CCOV: true
|
||||
- IMAGE: master-source
|
||||
CXX: clang++
|
||||
- IMAGE: noetic-source
|
||||
CLANG_TIDY: true
|
||||
env:
|
||||
CATKIN_LINT: true
|
||||
# CXXFLAGS: "-Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wno-strict-aliasing -Wno-sign-compare"
|
||||
UNDERLAY: /root/ws_moveit/install
|
||||
DOWNSTREAM_WORKSPACE: "github:ubi-agni/mtc_demos#master github:TAMS-Group/mtc_pour#master"
|
||||
TARGET_CMAKE_ARGS: >
|
||||
-DCMAKE_BUILD_TYPE=${{ matrix.env.CCOV && 'RelWithDebInfo' || 'Release' }}
|
||||
${{ matrix.env.CCOV && '-DCMAKE_CXX_FLAGS="--coverage"' || '' }}
|
||||
CCACHE_DIR: ${{ github.workspace }}/.ccache
|
||||
BASEDIR: /home/runner/work
|
||||
DOCKER_IMAGE: moveit/moveit:${{ matrix.env.IMAGE }}
|
||||
CACHE_PREFIX: "${{ matrix.env.IMAGE }}${{ matrix.env.CCOV && '-ccov' || '' }}"
|
||||
# perform full clang-tidy check only on manual trigger (workflow_dispatch), PRs do check changed files, otherwise nothing
|
||||
CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }}
|
||||
|
||||
name: "${{ matrix.env.IMAGE }}${{ matrix.env.CATKIN_LINT && ' + catkin_lint' || ''}}${{ matrix.env.CCOV && ' + ccov' || ''}}${{ matrix.env.IKFAST_TEST && ' + ikfast' || ''}}${{ matrix.env.CLANG_TIDY && ' + clang-tidy' || '' }}"
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
|
||||
- name: Cache ccache
|
||||
uses: pat-s/always-upload-cache@v2.1.3
|
||||
with:
|
||||
path: ${{ env.CCACHE_DIR }}
|
||||
key: ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}-${{ github.run_id }}
|
||||
restore-keys: |
|
||||
ccache-${{ env.CACHE_PREFIX }}-${{ github.sha }}
|
||||
ccache-${{ env.CACHE_PREFIX }}
|
||||
|
||||
- name: industrial_ci
|
||||
uses: ros-industrial/industrial_ci@master
|
||||
env: ${{ matrix.env || env }}
|
||||
|
||||
- name: Upload test artifacts (on failure)
|
||||
uses: actions/upload-artifact@v2
|
||||
if: failure()
|
||||
with:
|
||||
name: test-results
|
||||
path: ${{ env.BASEDIR }}/target_ws/**/test_results/**/*.xml
|
||||
23
.github/workflows/format.yaml
vendored
Normal file
23
.github/workflows/format.yaml
vendored
Normal file
@ -0,0 +1,23 @@
|
||||
# This is a format job. Pre-commit has a first-party GitHub action, so we use
|
||||
# that: https://github.com/pre-commit/action
|
||||
|
||||
name: Format
|
||||
|
||||
on:
|
||||
workflow_dispatch:
|
||||
pull_request:
|
||||
push:
|
||||
|
||||
jobs:
|
||||
pre-commit:
|
||||
name: pre-commit
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- uses: actions/setup-python@v2
|
||||
- name: Install clang-format-10
|
||||
run: sudo apt-get install clang-format-10
|
||||
- uses: rhaschke/install-catkin_lint-action@v1.0
|
||||
with:
|
||||
distro: noetic
|
||||
- uses: pre-commit/action@v2.0.0
|
||||
20
.github/workflows/format.yml
vendored
20
.github/workflows/format.yml
vendored
@ -1,20 +0,0 @@
|
||||
# This is a format job. Pre-commit has a first-party GitHub action, so we use
|
||||
# that: https://github.com/pre-commit/action
|
||||
|
||||
name: Format
|
||||
|
||||
on:
|
||||
workflow_dispatch:
|
||||
pull_request:
|
||||
push:
|
||||
|
||||
jobs:
|
||||
pre-commit:
|
||||
name: Format
|
||||
runs-on: ubuntu-latest
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- uses: actions/setup-python@v2
|
||||
- name: Install clang-format-10
|
||||
run: sudo apt-get install clang-format-10
|
||||
- uses: pre-commit/action@v2.0.0
|
||||
@ -26,6 +26,12 @@ repos:
|
||||
- id: debug-statements
|
||||
- id: end-of-file-fixer
|
||||
- id: mixed-line-ending
|
||||
- id: trailing-whitespace
|
||||
|
||||
- repo: https://github.com/psf/black
|
||||
rev: 20.8b1
|
||||
hooks:
|
||||
- id: black
|
||||
|
||||
- repo: local
|
||||
hooks:
|
||||
@ -36,12 +42,10 @@ repos:
|
||||
language: system
|
||||
files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$
|
||||
args: ['-fallback-style=none', '-i']
|
||||
|
||||
- repo: local
|
||||
hooks:
|
||||
- id: misspelled-moveit
|
||||
name: misspelled-moveit
|
||||
description: MoveIt should be spelled exactly as MoveIt
|
||||
language: pygrep
|
||||
entry: Moveit|MoveIt!
|
||||
exclude: .pre-commit-config.yaml|README.md
|
||||
- id: catkin_lint
|
||||
name: catkin_lint
|
||||
description: Check package.xml and cmake files
|
||||
entry: catkin_lint .
|
||||
language: system
|
||||
always_run: true
|
||||
pass_filenames: false
|
||||
|
||||
14
.rosinstall
14
.rosinstall
@ -1,14 +0,0 @@
|
||||
# This file is intended for users who want to build MTC and its demos from source.
|
||||
# Using wstool, users can download relevant MTC-related source packages.
|
||||
- git:
|
||||
local-name: moveit_task_constructor
|
||||
uri: https://github.com/ros-planning/moveit_task_constructor.git
|
||||
version: master
|
||||
- git:
|
||||
local-name: mtc_demos
|
||||
uri: https://github.com/ubi-agni/mtc_demos.git
|
||||
version: master
|
||||
- git:
|
||||
local-name: mtc_pour
|
||||
uri: https://github.com/TAMS-Group/mtc_pour.git
|
||||
version: master
|
||||
27
.travis.yml
27
.travis.yml
@ -1,27 +0,0 @@
|
||||
# This config file for Travis CI utilizes https://github.com/ros-planning/moveit_ci .
|
||||
os: linux
|
||||
dist: bionic
|
||||
services:
|
||||
- docker
|
||||
language: cpp
|
||||
compiler: gcc
|
||||
cache: ccache
|
||||
|
||||
notifications:
|
||||
email: true
|
||||
|
||||
env:
|
||||
global:
|
||||
- DOCKER_IMAGE=moveit/moveit:melodic-source
|
||||
- UPSTREAM_WORKSPACE=.rosinstall
|
||||
|
||||
jobs:
|
||||
- env: TEST=code-coverage
|
||||
- compiler: clang
|
||||
env: DOCKER_IMAGE=moveit/moveit:master-source
|
||||
|
||||
before_script:
|
||||
- git clone -q --depth=1 https://github.com/ros-planning/moveit_ci.git .moveit_ci
|
||||
|
||||
script:
|
||||
- .moveit_ci/travis.sh
|
||||
@ -15,6 +15,7 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
catkin_package(
|
||||
LIBRARIES $PROJECT_NAME}
|
||||
CATKIN_DEPENDS
|
||||
actionlib
|
||||
moveit_task_constructor_msgs
|
||||
std_msgs
|
||||
)
|
||||
|
||||
@ -82,8 +82,8 @@ public:
|
||||
template <typename Term, typename Signature = decltype(signatureMatcher(std::declval<Term>()))>
|
||||
LambdaCostTerm(const Term& t) : LambdaCostTerm{ Signature{ t } } {}
|
||||
|
||||
LambdaCostTerm(const SubTrajectorySignature&);
|
||||
LambdaCostTerm(const SubTrajectoryShortSignature&);
|
||||
LambdaCostTerm(const SubTrajectorySignature& term);
|
||||
LambdaCostTerm(const SubTrajectoryShortSignature& term);
|
||||
|
||||
double operator()(const SubTrajectory& s, std::string& comment) const override;
|
||||
|
||||
@ -105,7 +105,7 @@ class Constant : public CostTerm
|
||||
public:
|
||||
Constant(double c) : cost{ c } {};
|
||||
|
||||
double operator()(const SubTrajectory&, std::string&) const override;
|
||||
double operator()(const SubTrajectory& s, std::string& comment) const override;
|
||||
double operator()(const SolutionSequence& s, std::string& comment) const override;
|
||||
double operator()(const WrappedSolution& s, std::string& comment) const override;
|
||||
|
||||
@ -117,14 +117,14 @@ class PathLength : public TrajectoryCostTerm
|
||||
{
|
||||
// TODO(v4hn): allow to consider specific joints only
|
||||
public:
|
||||
double operator()(const SubTrajectory&, std::string&) const override;
|
||||
double operator()(const SubTrajectory& s, std::string& comment) const override;
|
||||
};
|
||||
|
||||
/// execution duration of the whole trajectory
|
||||
class TrajectoryDuration : public TrajectoryCostTerm
|
||||
{
|
||||
public:
|
||||
double operator()(const SubTrajectory&, std::string&) const override;
|
||||
double operator()(const SubTrajectory& s, std::string& comment) const override;
|
||||
};
|
||||
|
||||
/** length of Cartesian trajection of a link */
|
||||
@ -135,7 +135,7 @@ public:
|
||||
|
||||
std::string link_name;
|
||||
|
||||
double operator()(const SubTrajectory&, std::string&) const override;
|
||||
double operator()(const SubTrajectory& s, std::string& comment) const override;
|
||||
};
|
||||
|
||||
/** inverse distance to collision
|
||||
|
||||
@ -462,15 +462,14 @@ void SerialContainer::onNewSolution(const SolutionBase& current) {
|
||||
|
||||
// collect (and sort) all solutions spanning from start to end of this container
|
||||
ordered<SolutionSequencePtr> sorted;
|
||||
SolutionSequence::container_type solution;
|
||||
solution.reserve(children.size());
|
||||
for (auto& in : incoming.solutions) {
|
||||
for (auto& out : outgoing.solutions) {
|
||||
InterfaceState::Priority prio = in.second + InterfaceState::Priority(1u, current.cost()) + out.second;
|
||||
assert(prio.enabled());
|
||||
// found a complete solution path connecting start to end?
|
||||
if (prio.depth() == children.size()) {
|
||||
assert(solution.empty());
|
||||
SolutionSequence::container_type solution;
|
||||
solution.reserve(children.size());
|
||||
// insert incoming solutions in reverse order
|
||||
solution.insert(solution.end(), in.first.rbegin(), in.first.rend());
|
||||
// insert current solution
|
||||
|
||||
@ -45,11 +45,12 @@
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
#include <boost/format.hpp>
|
||||
#include <utility>
|
||||
|
||||
namespace moveit {
|
||||
namespace task_constructor {
|
||||
|
||||
double CostTerm::operator()(const SubTrajectory& s, std::string&) const {
|
||||
double CostTerm::operator()(const SubTrajectory& s, std::string& /*comment*/) const {
|
||||
return s.cost();
|
||||
}
|
||||
|
||||
@ -85,7 +86,7 @@ LambdaCostTerm::LambdaCostTerm(const SubTrajectorySignature& term)
|
||||
: term_{ [term](const SolutionBase& s, std::string& c) { return term(static_cast<const SubTrajectory&>(s), c); } } {}
|
||||
|
||||
LambdaCostTerm::LambdaCostTerm(const SubTrajectoryShortSignature& term)
|
||||
: term_{ [term](const SolutionBase& s, std::string&) { return term(static_cast<const SubTrajectory&>(s)); } } {}
|
||||
: term_{ [term](const SolutionBase& s, std::string& /*c*/) { return term(static_cast<const SubTrajectory&>(s)); } } {}
|
||||
|
||||
double LambdaCostTerm::operator()(const SubTrajectory& s, std::string& comment) const {
|
||||
assert(bool{ term_ });
|
||||
@ -94,19 +95,19 @@ double LambdaCostTerm::operator()(const SubTrajectory& s, std::string& comment)
|
||||
|
||||
namespace cost {
|
||||
|
||||
double Constant::operator()(const SubTrajectory&, std::string&) const {
|
||||
double Constant::operator()(const SubTrajectory& /*s*/, std::string& /*comment*/) const {
|
||||
return cost;
|
||||
}
|
||||
|
||||
double Constant::operator()(const SolutionSequence&, std::string&) const {
|
||||
double Constant::operator()(const SolutionSequence& /*s*/, std::string& /*comment*/) const {
|
||||
return cost;
|
||||
}
|
||||
|
||||
double Constant::operator()(const WrappedSolution&, std::string&) const {
|
||||
double Constant::operator()(const WrappedSolution& /*s*/, std::string& /*comment*/) const {
|
||||
return cost;
|
||||
}
|
||||
|
||||
double PathLength::operator()(const SubTrajectory& s, std::string&) const {
|
||||
double PathLength::operator()(const SubTrajectory& s, std::string& /*comment*/) const {
|
||||
const auto& traj = s.trajectory();
|
||||
|
||||
if (traj == nullptr)
|
||||
@ -118,7 +119,7 @@ double PathLength::operator()(const SubTrajectory& s, std::string&) const {
|
||||
return path_length;
|
||||
}
|
||||
|
||||
double TrajectoryDuration::operator()(const SubTrajectory& s, std::string&) const {
|
||||
double TrajectoryDuration::operator()(const SubTrajectory& s, std::string& /*comment*/) const {
|
||||
return s.trajectory() ? s.trajectory()->getDuration() : 0.0;
|
||||
}
|
||||
|
||||
@ -150,12 +151,12 @@ double LinkMotion::operator()(const SubTrajectory& s, std::string& comment) cons
|
||||
Clearance::Clearance(bool with_world, bool cumulative, std::string group_property, Mode mode)
|
||||
: with_world{ with_world }
|
||||
, cumulative{ cumulative }
|
||||
, group_property{ group_property }
|
||||
, group_property{ std::move(group_property) }
|
||||
, mode{ mode }
|
||||
, distance_to_cost{ [](double d) { return 1.0 / (d + 1e-5); } } {}
|
||||
|
||||
double Clearance::operator()(const SubTrajectory& s, std::string& comment) const {
|
||||
const std::string PREFIX{ "Clearance: " };
|
||||
static const std::string PREFIX{ "Clearance: " };
|
||||
|
||||
collision_detection::DistanceRequest request;
|
||||
request.type =
|
||||
|
||||
@ -91,6 +91,7 @@ moveit::core::JointModelGroup* merge(const std::vector<const moveit::core::Joint
|
||||
if (joints.size() != sum_joints) { // overlapping joint groups: analyse in more detail
|
||||
auto duplicates = findDuplicates(groups, joints);
|
||||
if (!duplicates.empty()) {
|
||||
// NOLINTNEXTLINE(readability-identifier-naming): getJointName is a function (variable)
|
||||
auto getJointName = boost::adaptors::transformed([](auto&& jm) { return jm->getName(); });
|
||||
std::string message("overlapping joints: " + boost::algorithm::join(duplicates | getJointName, ", "));
|
||||
throw std::runtime_error(message);
|
||||
|
||||
@ -74,7 +74,7 @@ bool JointInterpolationPlanner::plan(const planning_scene::PlanningSceneConstPtr
|
||||
|
||||
moveit::core::RobotState waypoint(from_state);
|
||||
double delta = d < 1e-6 ? 1.0 : props.get<double>("max_step") / d;
|
||||
for (double t = delta; t < 1.0; t += delta) {
|
||||
for (double t = delta; t < 1.0; t += delta) { // NOLINT(clang-analyzer-security.FloatLoopCounter)
|
||||
from_state.interpolate(to_state, t, waypoint);
|
||||
result->addSuffixWayPoint(waypoint, t);
|
||||
|
||||
|
||||
@ -77,7 +77,7 @@ struct PlannerCache
|
||||
planning_pipeline::PlanningPipelinePtr PipelinePlanner::create(const PipelinePlanner::Specification& spec) {
|
||||
static PlannerCache cache;
|
||||
|
||||
constexpr char const* PLUGIN_PARAMETER_NAME = "planning_plugin";
|
||||
static constexpr char const* PLUGIN_PARAMETER_NAME = "planning_plugin";
|
||||
|
||||
std::string pipeline_ns = spec.ns + "/planning_pipelines/" + spec.pipeline;
|
||||
// fallback to old structure for pipeline parameters in MoveIt
|
||||
|
||||
@ -81,7 +81,7 @@ void PredicateFilter::onNewSolution(const SolutionBase& s) {
|
||||
const auto& props = properties();
|
||||
|
||||
// false-positive in clang-tidy 10.0.0: predicate might change comment
|
||||
// NOLINTNEXTLINE(performance-unnecessary-value-param)
|
||||
// NOLINTNEXTLINE(performance-unnecessary-copy-initialization)
|
||||
std::string comment = s.comment();
|
||||
|
||||
double cost = s.cost();
|
||||
|
||||
@ -3,7 +3,7 @@
|
||||
<arg name="load_robot_description" value="true"/>
|
||||
</include>
|
||||
<include file="$(find pr2_moveit_config)/launch/move_group.launch">
|
||||
<arg name="allow_trajectory_execution" value="true"/>
|
||||
<arg name="allow_trajectory_execution" value="true"/>
|
||||
<arg name="fake_execution" value="true"/>
|
||||
<arg name="info" value="true"/>
|
||||
</include>
|
||||
|
||||
@ -3,7 +3,7 @@
|
||||
<arg name="load_robot_description" value="true"/>
|
||||
</include>
|
||||
<include file="$(find tams_ur5_setup_moveit_config)/launch/move_group.launch">
|
||||
<arg name="allow_trajectory_execution" value="true"/>
|
||||
<arg name="allow_trajectory_execution" value="true"/>
|
||||
<arg name="fake_execution" value="true"/>
|
||||
<arg name="info" value="true"/>
|
||||
</include>
|
||||
|
||||
@ -172,12 +172,12 @@ TEST(ContainerBase, positionForInsert) {
|
||||
|
||||
/* TODO: remove interface as it returns raw pointers */
|
||||
TEST(ContainerBase, findChild) {
|
||||
SerialContainer s, *c2;
|
||||
SerialContainer s;
|
||||
Stage *a, *b, *c1, *d;
|
||||
s.add(Stage::pointer(a = new NamedStage("a")));
|
||||
s.add(Stage::pointer(b = new NamedStage("b")));
|
||||
s.add(Stage::pointer(c1 = new NamedStage("c")));
|
||||
auto sub = ContainerBase::pointer(c2 = new SerialContainer("c"));
|
||||
auto sub = ContainerBase::pointer(new SerialContainer("c"));
|
||||
sub->add(Stage::pointer(d = new NamedStage("d")));
|
||||
s.add(std::move(sub));
|
||||
|
||||
@ -678,11 +678,11 @@ TEST(Task, move) {
|
||||
MOCK_ID = 0;
|
||||
Task t2 = std::move(t1);
|
||||
EXPECT_EQ(t2.stages()->numChildren(), 2u);
|
||||
EXPECT_EQ(t1.stages()->numChildren(), 0u);
|
||||
EXPECT_EQ(t1.stages()->numChildren(), 0u); // NOLINT(clang-analyzer-cplusplus.Move)
|
||||
|
||||
t1 = std::move(t2);
|
||||
EXPECT_EQ(t1.stages()->numChildren(), 2u);
|
||||
EXPECT_EQ(t2.stages()->numChildren(), 0u);
|
||||
EXPECT_EQ(t2.stages()->numChildren(), 0u); // NOLINT(clang-analyzer-cplusplus.Move)
|
||||
}
|
||||
|
||||
TEST(Task, reuse) {
|
||||
|
||||
@ -211,17 +211,17 @@ TEST(CostTerm, SetLambdaCostTerm) {
|
||||
|
||||
Standalone<SerialContainer> container(robot);
|
||||
auto stage{ std::make_unique<GeneratorMockup>() };
|
||||
stage->setCostTerm([](auto&&) { return 1.0; });
|
||||
stage->setCostTerm([](auto&& /*s*/) { return 1.0; });
|
||||
container.computeWithStages({ std::move(stage) });
|
||||
EXPECT_EQ(container.solutions().front()->cost(), 1.0) << "can use simple lambda signature";
|
||||
|
||||
stage = std::make_unique<GeneratorMockup>();
|
||||
stage->setCostTerm([](auto&&, auto&&) { return 1.0; });
|
||||
stage->setCostTerm([](auto&& /*s*/, auto&& /*comment*/) { return 1.0; });
|
||||
container.computeWithStages({ std::move(stage) });
|
||||
EXPECT_EQ(container.solutions().front()->cost(), 1.0) << "can use full lambda signature";
|
||||
|
||||
stage = std::make_unique<GeneratorMockup>();
|
||||
stage->setCostTerm([](auto&&, auto&& comment) {
|
||||
stage->setCostTerm([](auto&& /*s*/, auto&& comment) {
|
||||
comment = "I want the user to see this";
|
||||
return 1.0;
|
||||
});
|
||||
|
||||
@ -132,7 +132,7 @@ struct Connect : stages::Connect
|
||||
}
|
||||
};
|
||||
|
||||
constexpr double inf = std::numeric_limits<double>::infinity();
|
||||
constexpr double INF = std::numeric_limits<double>::infinity();
|
||||
unsigned int GeneratorMockup::id_ = 0;
|
||||
unsigned int ForwardMockup::id_ = 0;
|
||||
unsigned int BackwardMockup::id_ = 0;
|
||||
@ -181,7 +181,7 @@ TEST_F(ConnectConnect, SuccSucc) {
|
||||
// https://github.com/ros-planning/moveit_task_constructor/issues/218
|
||||
TEST_F(ConnectConnect, FailSucc) {
|
||||
add(task, new GeneratorMockup());
|
||||
add(task, new Connect({ inf }, true));
|
||||
add(task, new Connect({ INF }, true));
|
||||
add(task, new GeneratorMockup());
|
||||
add(task, new Connect());
|
||||
add(task, new GeneratorMockup());
|
||||
@ -194,7 +194,7 @@ using Pruning = TestBase;
|
||||
TEST_F(Pruning, PropagatorFailure) {
|
||||
auto back = add(task, new BackwardMockup());
|
||||
add(task, new GeneratorMockup({ 0 }));
|
||||
add(task, new ForwardMockup({ inf }));
|
||||
add(task, new ForwardMockup({ INF }));
|
||||
|
||||
EXPECT_FALSE(task.plan());
|
||||
ASSERT_EQ(task.solutions().size(), 0);
|
||||
@ -209,7 +209,7 @@ TEST_F(Pruning, PruningMultiForward) {
|
||||
// spawn two solutions for the only incoming state
|
||||
add(task, new ForwardMockup({ 0, 0 }, 2));
|
||||
// fail to extend the second solution
|
||||
add(task, new ForwardMockup({ 0, inf }));
|
||||
add(task, new ForwardMockup({ 0, INF }));
|
||||
|
||||
EXPECT_TRUE(task.plan());
|
||||
|
||||
@ -221,7 +221,7 @@ TEST_F(Pruning, PruningMultiForward) {
|
||||
|
||||
TEST_F(Pruning, ConnectConnectForward) {
|
||||
add(task, new GeneratorMockup());
|
||||
auto c1 = add(task, new Connect({ inf, 0 })); // 1st attempt is a failue
|
||||
auto c1 = add(task, new Connect({ INF, 0 })); // 1st attempt is a failue
|
||||
add(task, new GeneratorMockup({ 0, 10, 20 }));
|
||||
add(task, new ForwardMockup());
|
||||
auto c2 = add(task, new Connect());
|
||||
@ -244,8 +244,8 @@ TEST_F(Pruning, ConnectConnectBackward) {
|
||||
add(task, new GeneratorMockup({ 1, 2, 3 }));
|
||||
auto c1 = add(task, new Connect());
|
||||
add(task, new BackwardMockup());
|
||||
add(task, new GeneratorMockup({ 0, inf, 10, 20 })); // 2nd is a dummy to postpone creation of 3rd
|
||||
auto c2 = add(task, new Connect({ inf, 0 })); // 1st attempt is a failure
|
||||
add(task, new GeneratorMockup({ 0, INF, 10, 20 })); // 2nd is a dummy to postpone creation of 3rd
|
||||
auto c2 = add(task, new Connect({ INF, 0 })); // 1st attempt is a failure
|
||||
add(task, new GeneratorMockup());
|
||||
|
||||
task.plan();
|
||||
@ -262,7 +262,7 @@ TEST_F(Pruning, ConnectConnectBackward) {
|
||||
}
|
||||
|
||||
TEST_F(Pruning, PropagateIntoContainer) {
|
||||
add(task, new BackwardMockup({ inf }));
|
||||
add(task, new BackwardMockup({ INF }));
|
||||
add(task, new GeneratorMockup({ 0 }));
|
||||
|
||||
auto inner = add(task, new SerialContainer());
|
||||
@ -283,7 +283,7 @@ TEST_F(Pruning, PropagateFromContainerPull) {
|
||||
|
||||
auto inner = add(task, new SerialContainer());
|
||||
add(*inner, new ForwardMockup());
|
||||
add(*inner, new ForwardMockup({ inf }));
|
||||
add(*inner, new ForwardMockup({ INF }));
|
||||
|
||||
EXPECT_FALSE(task.plan());
|
||||
|
||||
@ -293,7 +293,7 @@ TEST_F(Pruning, PropagateFromContainerPull) {
|
||||
|
||||
TEST_F(Pruning, PropagateFromContainerPush) {
|
||||
auto inner = add(task, new SerialContainer());
|
||||
add(*inner, new BackwardMockup({ inf }));
|
||||
add(*inner, new BackwardMockup({ INF }));
|
||||
|
||||
add(task, new GeneratorMockup({ 0 }));
|
||||
auto con = add(task, new Connect());
|
||||
@ -310,7 +310,7 @@ TEST_F(Pruning, PropagateFromParallelContainerMultiplePaths) {
|
||||
add(task, new GeneratorMockup({ 0 }));
|
||||
auto inner = add(task, new Alternatives());
|
||||
|
||||
add(*inner, new ForwardMockup({ inf }));
|
||||
add(*inner, new ForwardMockup({ INF }));
|
||||
auto serial = add(*inner, new SerialContainer());
|
||||
add(*serial, new Connect());
|
||||
add(*serial, new GeneratorMockup({ 0 }));
|
||||
|
||||
@ -15,5 +15,6 @@
|
||||
<depend>moveit_ros_planning_interface</depend>
|
||||
<depend>moveit_core</depend>
|
||||
<depend>rosparam_shortcuts</depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<exec_depend>moveit_resources_panda_moveit_config</exec_depend>
|
||||
</package>
|
||||
|
||||
@ -64,7 +64,7 @@ class SubPanel : public QWidget
|
||||
public:
|
||||
SubPanel(QWidget* parent = nullptr) : QWidget(parent) {}
|
||||
|
||||
virtual void save(rviz::Config config) {}
|
||||
virtual void save(rviz::Config config) {} // NOLINT(performance-unnecessary-value-param)
|
||||
virtual void load(const rviz::Config& config) {}
|
||||
|
||||
Q_SIGNALS:
|
||||
@ -159,7 +159,7 @@ private:
|
||||
Q_PRIVATE_SLOT(d_ptr, void _q_configureInsertedModels(QModelIndex, int, int));
|
||||
|
||||
Q_SIGNALS:
|
||||
void oldTaskHandlingChanged(int);
|
||||
void oldTaskHandlingChanged(int old_task_handling);
|
||||
};
|
||||
|
||||
class GlobalSettingsWidgetPrivate;
|
||||
|
||||
@ -82,6 +82,7 @@ public:
|
||||
void configureTaskListModel(TaskListModel* model);
|
||||
/// configure all TaskListModels that were already created when TaskView gets instantiated
|
||||
void configureExistingModels();
|
||||
// NOLINTNEXTLINE(readability-identifier-naming)
|
||||
/// configure newly inserted models
|
||||
void _q_configureInsertedModels(const QModelIndex& parent, int first, int last);
|
||||
|
||||
|
||||
Loading…
Reference in New Issue
Block a user