Skip to content

Commit

Permalink
Add Generator::spawn(from, to, trajectory) variant (#546)
Browse files Browse the repository at this point in the history
  • Loading branch information
DaniGarciaLopez authored Mar 20, 2024
1 parent 55c4b52 commit 560aa0a
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 8 deletions.
1 change: 1 addition & 0 deletions core/include/moveit/task_constructor/stage.h
Original file line number Diff line number Diff line change
Expand Up @@ -365,6 +365,7 @@ class Generator : public ComputeBase

virtual bool canCompute() const = 0;
virtual void compute() = 0;
void spawn(InterfaceState&& from, InterfaceState&& to, SubTrajectory&& trajectory);
void spawn(InterfaceState&& state, SubTrajectory&& trajectory);
void spawn(InterfaceState&& state, double cost) {
SubTrajectory trajectory;
Expand Down
1 change: 1 addition & 0 deletions core/include/moveit/task_constructor/stage_p.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,7 @@ class StagePrivate
void sendBackward(InterfaceState&& from, const InterfaceState& to, const SolutionBasePtr& solution);
template <Interface::Direction>
inline void send(const InterfaceState& start, InterfaceState&& end, const SolutionBasePtr& solution);
void spawn(InterfaceState&& from, InterfaceState&& to, const SolutionBasePtr& solution);
void spawn(InterfaceState&& state, const SolutionBasePtr& solution);
void connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution);

Expand Down
24 changes: 16 additions & 8 deletions core/src/stage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,28 +219,32 @@ void StagePrivate::sendBackward(InterfaceState&& from, const InterfaceState& to,
newSolution(solution);
}

void StagePrivate::spawn(InterfaceState&& state, const SolutionBasePtr& solution) {
void StagePrivate::spawn(InterfaceState&& from, InterfaceState&& to, const SolutionBasePtr& solution) {
assert(prevEnds() && nextStarts());

computeCost(state, state, *solution);
computeCost(from, to, *solution);

if (!storeSolution(solution, nullptr, nullptr))
return; // solution dropped

auto from = states_.insert(states_.end(), InterfaceState(state)); // copy
auto to = states_.insert(states_.end(), std::move(state));
auto from_it = states_.insert(states_.end(), std::move(from));
auto to_it = states_.insert(states_.end(), std::move(to));

solution->setStartState(*from);
solution->setEndState(*to);
solution->setStartState(*from_it);
solution->setEndState(*to_it);

if (!solution->isFailure()) {
prevEnds()->add(*from);
nextStarts()->add(*to);
prevEnds()->add(*from_it);
nextStarts()->add(*to_it);
}

newSolution(solution);
}

void StagePrivate::spawn(InterfaceState&& state, const SolutionBasePtr& solution) {
spawn(InterfaceState(state), std::move(state), solution);
}

void StagePrivate::connect(const InterfaceState& from, const InterfaceState& to, const SolutionBasePtr& solution) {
computeCost(from, to, *solution);

Expand Down Expand Up @@ -688,6 +692,10 @@ void GeneratorPrivate::compute() {
Generator::Generator(GeneratorPrivate* impl) : ComputeBase(impl) {}
Generator::Generator(const std::string& name) : Generator(new GeneratorPrivate(this, name)) {}

void Generator::spawn(InterfaceState&& from, InterfaceState&& to, SubTrajectory&& t) {
pimpl()->spawn(std::move(from), std::move(to), std::make_shared<SubTrajectory>(std::move(t)));
}

void Generator::spawn(InterfaceState&& state, SubTrajectory&& t) {
pimpl()->spawn(std::move(state), std::make_shared<SubTrajectory>(std::move(t)));
}
Expand Down

0 comments on commit 560aa0a

Please sign in to comment.