Skip to content

Commit fdd5ff8

Browse files
committed
templatize: pullInterface(dir) -> pullInterface<dir>()
Also remove unused pushInterface(dir)
1 parent a31e52d commit fdd5ff8

File tree

3 files changed

+16
-15
lines changed

3 files changed

+16
-15
lines changed

core/include/moveit/task_constructor/stage_p.h

Lines changed: 12 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -100,17 +100,9 @@ class StagePrivate
100100
inline InterfaceConstPtr prevEnds() const { return prev_ends_.lock(); }
101101
inline InterfaceConstPtr nextStarts() const { return next_starts_.lock(); }
102102

103-
/// direction-based access to pull/push interfaces
104-
inline InterfacePtr& pullInterface(Interface::Direction dir) { return dir == Interface::FORWARD ? starts_ : ends_; }
105-
inline InterfacePtr pushInterface(Interface::Direction dir) {
106-
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
107-
}
108-
inline InterfaceConstPtr pullInterface(Interface::Direction dir) const {
109-
return dir == Interface::FORWARD ? starts_ : ends_;
110-
}
111-
inline InterfaceConstPtr pushInterface(Interface::Direction dir) const {
112-
return dir == Interface::FORWARD ? next_starts_.lock() : prev_ends_.lock();
113-
}
103+
/// direction-based access to pull interface
104+
template <Interface::Direction dir>
105+
inline InterfacePtr pullInterface();
114106

115107
/// set parent of stage
116108
/// enforce only one parent exists
@@ -204,6 +196,15 @@ class StagePrivate
204196
PIMPL_FUNCTIONS(Stage)
205197
std::ostream& operator<<(std::ostream& os, const StagePrivate& stage);
206198

199+
template <>
200+
inline InterfacePtr StagePrivate::pullInterface<Interface::FORWARD>() {
201+
return starts_;
202+
}
203+
template <>
204+
inline InterfacePtr StagePrivate::pullInterface<Interface::BACKWARD>() {
205+
return ends_;
206+
}
207+
207208
template <>
208209
inline void StagePrivate::send<Interface::FORWARD>(const InterfaceState& start, InterfaceState&& end,
209210
const SolutionBasePtr& solution) {

core/src/container.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -715,7 +715,7 @@ void ParallelContainerBasePrivate::validateConnectivity() const {
715715
template <Interface::Direction dir>
716716
void ParallelContainerBasePrivate::onNewExternalState(Interface::iterator external, bool updated) {
717717
for (const Stage::pointer& stage : children())
718-
copyState<dir>(external, stage->pimpl()->pullInterface(dir), updated);
718+
copyState<dir>(external, stage->pimpl()->pullInterface<dir>(), updated);
719719
}
720720

721721
ParallelContainerBase::ParallelContainerBase(ParallelContainerBasePrivate* impl) : ContainerBase(impl) {}

core/src/stage.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -713,9 +713,9 @@ ConnectingPrivate::StatePair ConnectingPrivate::make_pair<Interface::FORWARD>(In
713713
template <Interface::Direction dir>
714714
void ConnectingPrivate::newState(Interface::iterator it, bool updated) {
715715
auto parent_pimpl = parent()->pimpl();
716-
Interface::DisableNotify disable_source_interface(*pullInterface(dir));
716+
Interface::DisableNotify disable_source_interface(*pullInterface<dir>());
717717
if (updated) {
718-
if (pullInterface(opposite<dir>())->notifyEnabled()) // suppress recursive loop
718+
if (pullInterface<opposite<dir>()>()->notifyEnabled()) // suppress recursive loop
719719
{
720720
// If status has changed, propagate the update to the opposite side
721721
auto status = it->priority().status();
@@ -747,7 +747,7 @@ void ConnectingPrivate::newState(Interface::iterator it, bool updated) {
747747
pending.sort();
748748
} else { // new state: insert all pairs with other interface
749749
assert(it->priority().enabled()); // new solutions are feasible, aren't they?
750-
InterfacePtr other_interface = pullInterface(dir);
750+
InterfacePtr other_interface = pullInterface<dir>();
751751
bool have_enabled_opposites = false;
752752
for (Interface::iterator oit = other_interface->begin(), oend = other_interface->end(); oit != oend; ++oit) {
753753
if (!static_cast<Connecting*>(me_)->compatible(*it, *oit))

0 commit comments

Comments
 (0)