Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
76 commits
Select commit Hold shift + click to select a range
f32e747
add hook to ParallelContainerBase to customize state propagation
v4hn Aug 18, 2021
8719b1c
Implement state-wise Fallbacks
v4hn Aug 19, 2021
3d5cecd
fallback generator can run a single job per compute call
v4hn Sep 2, 2021
aa733fc
simplify onNewFailure
v4hn Sep 2, 2021
5a9cfc5
cleanup: get rid of superfluous parameter
v4hn Sep 2, 2021
9a583ab
run only one compute step per call
v4hn Sep 3, 2021
22809c0
order external states
v4hn Sep 10, 2021
887da5b
fix fallbacks logic
v4hn Sep 14, 2021
b6ac5b0
add demo illustrating useful fallbacks behavior
v4hn Sep 15, 2021
66e141d
Fix printChildrenInterfaces()
rhaschke Nov 15, 2021
011e4be
Add more pruning tests
rhaschke Nov 18, 2021
c617e33
Disable failing tests
rhaschke Nov 19, 2021
718170a
Always skip pruning if there exist alternative enabled solutions
rhaschke Nov 19, 2021
97c2130
Improve readability
rhaschke Nov 19, 2021
1ddf7dd
Never remove pending CONNECT pairs
rhaschke Nov 19, 2021
4170a1c
Drop unused and misleading Direction enums
rhaschke Nov 19, 2021
29d1e44
Rework updatePriority() functions
rhaschke Nov 19, 2021
06ae5dd
Fix hasPendingOpposites()
rhaschke Nov 19, 2021
52dc494
Fix test Pruning.NoPruningIfAlternativesExist
rhaschke Nov 19, 2021
1dda3d1
Switch order of function declarations
rhaschke Nov 19, 2021
3c4ef68
Rename Interface::Status FAILED -> ARMED
rhaschke Nov 20, 2021
ab9af6a
Recursively re-enable states when matching an ARMED state
rhaschke Nov 20, 2021
ffb8598
Recursively prune new CONNECT state if there is no enabled opposite
rhaschke Nov 20, 2021
9d37495
Recombine both variants of Interface::updatePriority()
rhaschke Nov 21, 2021
3648db4
Never overwrite ARMED with PRUNED
rhaschke Nov 21, 2021
a31e52d
Propagate status across Connecting gap
rhaschke Nov 21, 2021
fdd5ff8
templatize: pullInterface(dir) -> pullInterface<dir>()
rhaschke Nov 21, 2021
a48b932
Distinguish STATUS and PRIORITY updates in notify() callbacks
rhaschke Nov 21, 2021
aef9916
Propagate either STATUS or PRIORITY updates into a container
rhaschke Nov 21, 2021
b783173
GENERATE: return correct canCompute() result as early as possible
rhaschke Sep 9, 2021
6653c48
Rename: computeFromExternal -> computePropagate
rhaschke Sep 16, 2021
e5b20ac
Fix pruning
rhaschke Sep 16, 2021
c33b196
Handle updates on external states
rhaschke Sep 16, 2021
dcb6857
Simplify computePropagate()
rhaschke Sep 16, 2021
5c235ab
debugging helper function
rhaschke Sep 17, 2021
2e63c15
Reintroduce pending state
rhaschke Sep 17, 2021
a0bc060
Enable tests
rhaschke Nov 22, 2021
c822fd3
Remove logger configuration
rhaschke Nov 22, 2021
b84bb87
pre-commit autoupdate
rhaschke Nov 24, 2021
e67b325
static TaskPrivate::swap() -> ContainerBasePrivate::operator=()
rhaschke Nov 23, 2021
8dd8022
Factorize implementation of FallbacksPrivate into 3 classes
rhaschke Nov 23, 2021
070c6e9
Disable failing test FallbacksFixtureConnect.connectStageInsideFallbacks
rhaschke Nov 25, 2021
7237e81
Rework FallbacksPrivate*
rhaschke Nov 24, 2021
e296bd7
Simplify: job_has_solutions_
rhaschke Nov 24, 2021
b4a9e20
Stage::reset() should reset total_compute_time_ (#310)
rhaschke Nov 25, 2021
0587129
CI: asan with debug symbols
rhaschke Nov 25, 2021
4be4486
Improve debug output
rhaschke Nov 15, 2021
191ff25
add tests for MoveRelative
v4hn Dec 14, 2021
84f96ec
MoveRelative: Interpret direction relative to IKFrame
v4hn Dec 14, 2021
f9c0a89
Merge pull request #320 from v4hn/pr-master-fix-move-rel-ikframe
v4hn Dec 20, 2021
7dbe0b8
Return MoveItErrorCode from task::plan (#319)
JafarAbdi Jan 2, 2022
9630f4d
ComputeIK: Improve markers
rhaschke Sep 12, 2021
184fab8
GeneratePlacePose: add property 'allow_z_flip'
rhaschke Sep 15, 2021
b205674
Generalize connectStageInsideFallbacks
rhaschke Nov 26, 2021
442d39a
Improve comments
rhaschke Nov 29, 2021
b2c116e
reset(new Interface()) -> std::make_shared<Interface>()
rhaschke Nov 29, 2021
7af3d8e
Improve readability
rhaschke Jan 5, 2022
b82b70e
FallbacksPrivate::nextChild()
rhaschke Jan 5, 2022
986d3c8
FallbacksPrivateCommon: shared between Generator + Propagator
rhaschke Jan 5, 2022
7a04a9f
ParallelContainerBasePrivate::propagateStateTo*All*Children
rhaschke Jan 5, 2022
4cc1f56
FallbacksPrivateConnect
rhaschke Jan 5, 2022
5956e70
Merge PR #311: fix Fallbacks
rhaschke Jan 5, 2022
c7b2067
Merge PR #309: Fix Pruning
rhaschke Jan 5, 2022
b2c990b
core: export rviz_marker_tools dependency
rhaschke Jan 7, 2022
ca38d11
Enable InterfaceState's copy operator
rhaschke Feb 2, 2022
ee7cec2
FixedState: ignore_collisions=false
rhaschke Mar 3, 2022
5310f90
operator<< for Interface::Direction
rhaschke Mar 4, 2022
0a3dd3a
properly set comment markAsFailure without prior comment
v4hn Mar 4, 2022
6d104e8
polish: FixedState supports collision checking
v4hn Mar 4, 2022
8d7225d
Connect: better document suppressing recursive loop
rhaschke Mar 4, 2022
096c671
Pruning: Relax too strong assertion: PRUNED => !ARMED
rhaschke Mar 4, 2022
8beb0f4
Update black version (#348)
stephanie-eng Mar 29, 2022
9026ac8
Make TimeParamerization configurable (#339)
rhaschke May 8, 2022
d2918f1
Pruning: Relax too strong assertion: PRUNED => !ARMED (#340)
rhaschke May 8, 2022
11b8185
Merge https://github.com/ros-planning/moveit/commit/d2918f130d5bbcd7a…
JafarAbdi May 26, 2022
d6284ea
Remove macros to check supported features
JafarAbdi May 26, 2022
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ jobs:
-e PRELOAD=libasan.so.5
-e LSAN_OPTIONS="suppressions=$PWD/.github/workflows/lsan.suppressions,fast_unwind_on_malloc=0"
-e ASAN_OPTIONS="new_delete_type_mismatch=0,alloc_dealloc_mismatch=0"
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1"
TARGET_CMAKE_ARGS: -DCMAKE_CXX_FLAGS="-fsanitize=address -fno-omit-frame-pointer -O1 -g"

env:
CLANG_TIDY_ARGS: --fix --fix-errors --format-style=file
Expand Down
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
repos:
# Standard hooks
- repo: https://github.com/pre-commit/pre-commit-hooks
rev: v3.4.0
rev: v4.0.1
hooks:
- id: check-added-large-files
- id: check-case-conflict
Expand Down
6 changes: 3 additions & 3 deletions core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@ find_package(rviz_marker_tools REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(visualization_msgs REQUIRED)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 17)
endif()
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_EXTENSIONS OFF)

add_compile_options(-fvisibility-inlines-hidden)

Expand Down
15 changes: 11 additions & 4 deletions core/include/moveit/task_constructor/container.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,7 @@ class Alternatives : public ParallelContainerBase
void onNewSolution(const SolutionBase& s) override;
};

class FallbacksPrivate;
/** Plan for different alternatives in sequence.
*
* Try to find feasible solutions using first child. Only if this fails,
Expand All @@ -158,17 +159,23 @@ class Alternatives : public ParallelContainerBase
*/
class Fallbacks : public ParallelContainerBase
{
mutable Stage* active_child_ = nullptr;
inline void replaceImpl();

public:
Fallbacks(const std::string& name = "fallbacks") : ParallelContainerBase(name) {}
PRIVATE_CLASS(Fallbacks);
Fallbacks(const std::string& name = "fallbacks");

void reset() override;
void init(const moveit::core::RobotModelConstPtr& robot_model) override;
bool canCompute() const override;
void compute() override;

protected:
Fallbacks(FallbacksPrivate* impl);
void onNewSolution(const SolutionBase& s) override;

private:
// not needed, we directly use corresponding virtual methods of FallbacksPrivate
bool canCompute() const final { return false; }
void compute() final {}
};

class MergerPrivate;
Expand Down
103 changes: 94 additions & 9 deletions core/include/moveit/task_constructor/container_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ namespace task_constructor {
class ContainerBasePrivate : public StagePrivate
{
friend class ContainerBase;
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);
friend class ConnectingPrivate; // needed propagate setStatus() in newState()

public:
using container_type = StagePrivate::container_type;
Expand Down Expand Up @@ -131,10 +131,11 @@ class ContainerBasePrivate : public StagePrivate
inline const auto& externalToInternalMap() const { return internal_external_.by<EXTERNAL>(); }

/// called by a (direct) child when a solution failed
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to);
virtual void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to);

protected:
ContainerBasePrivate(ContainerBase* me, const std::string& name);
ContainerBasePrivate& operator=(ContainerBasePrivate&& other);

// Set child's push interfaces: allow pushing if child requires it.
inline void setChildsPushBackwardInterface(StagePrivate* child) {
Expand All @@ -148,14 +149,19 @@ class ContainerBasePrivate : public StagePrivate
child->setNextStarts(allowed ? pending_forward_ : InterfacePtr());
}

/// Set ENABLED / PRUNED status of the solution tree starting from s into given direction
/// Set ENABLED/PRUNED status of a solution branch starting from target into the given direction
template <Interface::Direction dir>
void setStatus(const InterfaceState* s, InterfaceState::Status status);
void setStatus(const Stage* creator, const InterfaceState* source, const InterfaceState* target,
InterfaceState::Status status);

/// copy external_state to a child's interface and remember the link in internal_external map
/// Copy external_state to a child's interface and remember the link in internal_external map
template <Interface::Direction>
void copyState(Interface::iterator external, const InterfacePtr& target, bool updated);
/// lift solution from internal to external level
void copyState(Interface::iterator external, const InterfacePtr& target, Interface::UpdateFlags updated);
// non-template version
void copyState(Interface::Direction dir, Interface::iterator external, const InterfacePtr& target,
Interface::UpdateFlags updated);

/// Lift solution from internal to external level
void liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
const InterfaceState* internal_to);

Expand Down Expand Up @@ -228,12 +234,91 @@ class ParallelContainerBasePrivate : public ContainerBasePrivate
void validateInterfaces(const StagePrivate& child, InterfaceFlags& external, bool first = false) const;

private:
/// callback for new externally received states
/// notify callback for new externally received interface states
template <typename Interface::Direction>
void onNewExternalState(Interface::iterator external, bool updated);
void propagateStateToAllChildren(Interface::iterator external, Interface::UpdateFlags updated);

// override to customize behavior on received interface states (default: propagateStateToAllChildren())
virtual void initializeExternalInterfaces();
};
PIMPL_FUNCTIONS(ParallelContainerBase)

/* The Fallbacks container needs to implement different behaviour based on its interface.
* Thus, we implement 3 different classes: for Generator, Propagator, and Connect-like interfaces.
* FallbacksPrivate is the common base class for all of them, defining the common API
* to be used by the Fallbacks container.
* The actual interface-specific class is instantiated in initializeExternalInterfaces()
* resp. Fallbacks::replaceImpl() when the actual interface is known.
* The key difference between the 3 variants is how they advance to the next job. */
class FallbacksPrivate : public ParallelContainerBasePrivate
{
public:
FallbacksPrivate(Fallbacks* me, const std::string& name);
FallbacksPrivate(FallbacksPrivate&& other);

void initializeExternalInterfaces() final;
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to) override;

// virtual methods specific to each variant
virtual void onNewSolution(const SolutionBase& s);
virtual void reset() {}
};
PIMPL_FUNCTIONS(Fallbacks)

/* Class shared between FallbacksPrivateGenerator and FallbacksPrivatePropagator,
which both have the notion of a currently active child stage */
class FallbacksPrivateCommon : public FallbacksPrivate
{
public:
FallbacksPrivateCommon(FallbacksPrivate&& other) : FallbacksPrivate(std::move(other)) {}

/// Advance to next child
inline void nextChild();
/// Advance to the next job, assuming that the current child is exhausted on the current job.
virtual bool nextJob() = 0;

void reset() override;
bool canCompute() const override;
void compute() override;

container_type::const_iterator current_; // currently active child
};

/// Fallbacks implementation for GENERATOR interface
struct FallbacksPrivateGenerator : FallbacksPrivateCommon
{
FallbacksPrivateGenerator(FallbacksPrivate&& old);
bool nextJob() override;
};

/// Fallbacks implementation for FORWARD or BACKWARD interface
struct FallbacksPrivatePropagator : FallbacksPrivateCommon
{
FallbacksPrivatePropagator(FallbacksPrivate&& old);
void reset() override;
void onNewSolution(const SolutionBase& s) override;
bool nextJob() override;

Interface::Direction dir_; // propagation direction
Interface::iterator job_; // pointer to currently processed external state
bool job_has_solutions_; // flag indicating whether the current job generated solutions
};

/// Fallbacks implementation for CONNECT interface
struct FallbacksPrivateConnect : FallbacksPrivate
{
FallbacksPrivateConnect(FallbacksPrivate&& old);
void reset() override;
bool canCompute() const override;
void compute() override;
void onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to) override;

template <Interface::Direction dir>
void propagateStateUpdate(Interface::iterator external, Interface::UpdateFlags updated);

mutable container_type::const_iterator active_; // child picked for compute()
};

class WrapperBasePrivate : public ParallelContainerBasePrivate
{
friend class WrapperBase;
Expand Down
4 changes: 3 additions & 1 deletion core/include/moveit/task_constructor/merge.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <moveit/task_constructor/storage.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/trajectory_processing/time_parameterization.h>

namespace moveit {
namespace task_constructor {
Expand All @@ -57,6 +58,7 @@ moveit::core::JointModelGroup* merge(const std::vector<const moveit::core::Joint
*/
robot_trajectory::RobotTrajectoryPtr
merge(const std::vector<robot_trajectory::RobotTrajectoryConstPtr>& sub_trajectories,
const moveit::core::RobotState& base_state, moveit::core::JointModelGroup*& merged_group);
const moveit::core::RobotState& base_state, moveit::core::JointModelGroup*& merged_group,
const trajectory_processing::TimeParameterization& time_parameterization);
} // namespace task_constructor
} // namespace moveit
11 changes: 7 additions & 4 deletions core/include/moveit/task_constructor/moveit_compat.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,15 @@
#pragma once

#include <moveit/version.h>
#include <moveit/macros/class_forward.h>

#define MOVEIT_VERSION_GE(major, minor, patch) \
(MOVEIT_VERSION_MAJOR * 1'000'000 + MOVEIT_VERSION_MINOR * 1'000 + MOVEIT_VERSION_PATCH >= \
major * 1'000'000 + minor * 1'000 + patch)

// use object shape poses relative to a single object pose
#define MOVEIT_HAS_OBJECT_POSE 1

#define MOVEIT_HAS_STATE_RIGID_PARENT_LINK 0
#if !MOVEIT_VERSION_GE(3, 0, 0)
// the pointers are not yet available
namespace trajectory_processing {
MOVEIT_CLASS_FORWARD(TimeParameterization);
}
#endif
52 changes: 27 additions & 25 deletions core/include/moveit/task_constructor/stage_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ class StagePrivate
{
friend class Stage;
friend std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);
friend void swap(StagePrivate*& lhs, StagePrivate*& rhs);

public:
/// container type used to store children
Expand Down Expand Up @@ -100,17 +99,11 @@ class StagePrivate
inline InterfaceConstPtr prevEnds() const { return prev_ends_.lock(); }
inline InterfaceConstPtr nextStarts() const { return next_starts_.lock(); }

/// direction-based access to pull/push interfaces
inline InterfacePtr& pullInterface(Interface::Direction dir) { return dir == Interface::FORWARD ? starts_ : ends_; }
inline InterfacePtr pushInterface(Interface::Direction dir) {
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
}
inline InterfaceConstPtr pullInterface(Interface::Direction dir) const {
return dir == Interface::FORWARD ? starts_ : ends_;
}
inline InterfaceConstPtr pushInterface(Interface::Direction dir) const {
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
}
/// direction-based access to pull interface
template <Interface::Direction dir>
inline InterfacePtr pullInterface();
// non-template version
inline InterfacePtr pullInterface(Interface::Direction dir) { return dir == Interface::FORWARD ? starts_ : ends_; }

/// set parent of stage
/// enforce only one parent exists
Expand Down Expand Up @@ -165,6 +158,8 @@ class StagePrivate
void computeCost(const InterfaceState& from, const InterfaceState& to, SolutionBase& solution);

protected:
StagePrivate& operator=(StagePrivate&& other);

// associated/owning Stage instance
Stage* me_;

Expand Down Expand Up @@ -205,6 +200,15 @@ class StagePrivate
PIMPL_FUNCTIONS(Stage)
std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);

template <>
inline InterfacePtr StagePrivate::pullInterface<Interface::FORWARD>() {
return starts_;
}
template <>
inline InterfacePtr StagePrivate::pullInterface<Interface::BACKWARD>() {
return ends_;
}

template <>
inline void StagePrivate::send<Interface::FORWARD>(const InterfaceState& start, InterfaceState&& end,
const SolutionBasePtr& solution) {
Expand Down Expand Up @@ -301,6 +305,7 @@ PIMPL_FUNCTIONS(MonitoringGenerator)
class ConnectingPrivate : public ComputeBasePrivate
{
friend class Connecting;
friend struct FallbacksPrivateConnect;

public:
struct StatePair : std::pair<Interface::const_iterator, Interface::const_iterator>
Expand All @@ -311,18 +316,15 @@ class ConnectingPrivate : public ComputeBasePrivate
}
static inline bool less(const InterfaceState::Priority& lhsA, const InterfaceState::Priority& lhsB,
const InterfaceState::Priority& rhsA, const InterfaceState::Priority& rhsB) {
unsigned char lhs = (lhsA.enabled() << 1) | lhsB.enabled(); // combine bits into two-digit binary number
unsigned char rhs = (rhsA.enabled() << 1) | rhsB.enabled();
bool lhs = lhsA.enabled() && lhsB.enabled();
bool rhs = rhsA.enabled() && rhsB.enabled();

if (lhs == rhs) // if enabled status is identical
return lhsA + lhsB < rhsA + rhsB; // compare the sums of both contributions
// one of the states in each pair should be enabled
assert(lhs != 0b00 && rhs != 0b00);
// both states valid (b11)
if (lhs == 0b11)
return true;
if (rhs == 0b11)
return false;
return lhs < rhs; // disabled states in 1st component go before disabled states in 2nd component

// sort both-enabled pairs first
static_assert(true > false, "Comparing enabled states requires true > false");
return lhs > rhs;
}
};

Expand All @@ -334,7 +336,7 @@ class ConnectingPrivate : public ComputeBasePrivate

// Check whether there are pending feasible states that could connect to source
template <Interface::Direction dir>
bool hasPendingOpposites(const InterfaceState* source) const;
bool hasPendingOpposites(const InterfaceState* source, const InterfaceState* target) const;

std::ostream& printPendingPairs(std::ostream& os = std::cerr) const;

Expand All @@ -343,9 +345,9 @@ class ConnectingPrivate : public ComputeBasePrivate
template <Interface::Direction other>
inline StatePair make_pair(Interface::const_iterator first, Interface::const_iterator second);

// get informed when new start or end state becomes available
// notify callback to get informed about newly inserted (or updated) start or end states
template <Interface::Direction other>
void newState(Interface::iterator it, bool updated);
void newState(Interface::iterator it, Interface::UpdateFlags updated);

// ordered list of pending state pairs
ordered<StatePair> pending;
Expand Down
Loading