Skip to content

Commit 16387bc

Browse files
committed
support modifying wrappers in user stages
Possible features that require this interface might be - trajectory reparameterization, - trajectory optimization as post-processing (like MoveIt's CHOMP adapter), - multi-trajectory blending (similar to Pilz' sequence planner) Also remove invalid interfaces. Parallel containers must always forward solutions of their child stages, so simple spawning is not allowed without a child solution.
1 parent ef84fa3 commit 16387bc

File tree

4 files changed

+71
-56
lines changed

4 files changed

+71
-56
lines changed

core/include/moveit/task_constructor/container.h

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -126,12 +126,11 @@ class ParallelContainerBase : public ContainerBase
126126
/// lift child solution to external interface, adapting the costs and comment
127127
void liftSolution(const SolutionBase& solution, double cost, std::string comment);
128128

129-
/// spawn a new solution with given state as start and end
130-
void spawn(InterfaceState&& state, SubTrajectory&& trajectory);
131-
/// propagate a solution forwards
132-
void sendForward(const InterfaceState& from, InterfaceState&& to, SubTrajectory&& trajectory);
133-
/// propagate a solution backwards
134-
void sendBackward(InterfaceState&& from, const InterfaceState& to, SubTrajectory&& trajectory);
129+
/// lift a modified solution based on the solution of a child stage
130+
void liftModifiedSolution(SolutionBasePtr&& new_solution, const SolutionBase& child_solution);
131+
/// lift a modified solution, changing the (single!) new associated start or end InterfaceState
132+
void liftModifiedSolution(SolutionBasePtr&& new_solution, InterfaceState&& new_propagated_state,
133+
const SolutionBase& child_solution);
135134
};
136135

137136
/** Plan for different alternatives in parallel.

core/include/moveit/task_constructor/container_p.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -150,9 +150,9 @@ class ContainerBasePrivate : public StagePrivate
150150
/// copy external_state to a child's interface and remember the link in internal_external map
151151
template <Interface::Direction>
152152
void copyState(Interface::iterator external, const InterfacePtr& target, bool updated);
153-
/// lift solution from internal to external level
153+
/// lift solution from internal to external level, possibly replacing the generated InterfaceState with new_external
154154
void liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
155-
const InterfaceState* internal_to);
155+
const InterfaceState* internal_to, const InterfaceState* new_external = nullptr);
156156

157157
/// protected writable overloads
158158
inline auto& internalToExternalMap() { return internal_external_.left; }

core/src/container.cpp

Lines changed: 47 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -203,37 +203,49 @@ void ContainerBasePrivate::copyState(Interface::iterator external, const Interfa
203203
}
204204

205205
void ContainerBasePrivate::liftSolution(const SolutionBasePtr& solution, const InterfaceState* internal_from,
206-
const InterfaceState* internal_to) {
207-
computeCost(*internal_from, *internal_to, *solution);
208-
209-
// map internal to external states
210-
auto find_or_create_external = [this](const InterfaceState* internal, bool& created) -> InterfaceState* {
211-
auto it = internalToExternalMap().find(internal);
212-
if (it != internalToExternalMap().end())
213-
return const_cast<InterfaceState*>(it->second);
214-
215-
InterfaceState* external = storeState(InterfaceState(*internal));
216-
internalToExternalMap().insert(std::make_pair(internal, external));
217-
created = true;
206+
const InterfaceState* internal_to, const InterfaceState* new_external) {
207+
const bool create_from{ requiredInterface().testFlag(WRITES_PREV_END) };
208+
const bool create_to{ requiredInterface().testFlag(WRITES_NEXT_START) };
209+
210+
// external states, nullptr if they don't exist yet
211+
const InterfaceState* external_from{ create_from ? new_external : internalToExternalMap().at(internal_from) };
212+
const InterfaceState* external_to{ create_to ? new_external : internalToExternalMap().at(internal_to) };
213+
214+
// computeCost
215+
computeCost(external_from ? *external_from : InterfaceState(*internal_from),
216+
external_to ? *external_to : InterfaceState(*internal_to), *solution);
217+
218+
// storeSolution
219+
if (!storeSolution(solution, external_from, external_to)) {
220+
return;
221+
}
222+
223+
auto create_state = [this, new_external](const InterfaceState& internal) {
224+
InterfaceState* external{ storeState(new_external ? InterfaceState{ *new_external } :
225+
InterfaceState{ internal }) };
226+
internalToExternalMap().insert(std::make_pair(&internal, external));
218227
return external;
219228
};
220-
bool created_from = false;
221-
bool created_to = false;
222-
InterfaceState* external_from = find_or_create_external(internal_from, created_from);
223-
InterfaceState* external_to = find_or_create_external(internal_to, created_to);
224229

225-
if (!storeSolution(solution, external_from, external_to))
226-
return;
230+
if (create_from)
231+
external_from = create_state(*internal_from);
232+
if (create_to)
233+
external_to = create_state(*internal_to);
234+
235+
assert(external_from);
236+
assert(external_to);
227237

228-
// connect solution to start/end state
238+
// connect solution to states
229239
solution->setStartState(*external_from);
230240
solution->setEndState(*external_to);
231241

232-
// spawn created states in external interfaces
233-
if (created_from)
234-
prevEnds()->add(*external_from);
235-
if (created_to)
236-
nextStarts()->add(*external_to);
242+
// spawn new external states
243+
if (!solution->isFailure()) {
244+
if (create_from)
245+
prevEnds()->add(*const_cast<InterfaceState*>(external_from));
246+
if (create_to)
247+
nextStarts()->add(*const_cast<InterfaceState*>(external_to));
248+
}
237249

238250
newSolution(solution);
239251
}
@@ -737,16 +749,20 @@ void ParallelContainerBase::liftSolution(const SolutionBase& solution, double co
737749
solution.start(), solution.end());
738750
}
739751

740-
void ParallelContainerBase::spawn(InterfaceState&& state, SubTrajectory&& t) {
741-
pimpl()->StagePrivate::spawn(std::move(state), std::make_shared<SubTrajectory>(std::move(t)));
742-
}
752+
void ParallelContainerBase::liftModifiedSolution(SolutionBasePtr&& modified_solution, const SolutionBase &child_solution) {
753+
// child_solution is correctly prepared by a child of this container
754+
assert(child_solution.creator());
755+
assert(child_solution.creator()->parent() == this);
743756

744-
void ParallelContainerBase::sendForward(const InterfaceState& from, InterfaceState&& to, SubTrajectory&& t) {
745-
pimpl()->StagePrivate::sendForward(from, std::move(to), std::make_shared<SubTrajectory>(std::move(t)));
757+
pimpl()->liftSolution(std::move(modified_solution),
758+
child_solution.start(), child_solution.end());
746759
}
747760

748-
void ParallelContainerBase::sendBackward(InterfaceState&& from, const InterfaceState& to, SubTrajectory&& t) {
749-
pimpl()->StagePrivate::sendBackward(std::move(from), to, std::make_shared<SubTrajectory>(std::move(t)));
761+
void ParallelContainerBase::liftModifiedSolution(SolutionBasePtr &&new_solution, InterfaceState &&new_propagated_state, const SolutionBase &child_solution) {
762+
assert(child_solution.creator());
763+
assert(child_solution.creator()->parent() == this);
764+
765+
pimpl()->liftSolution(std::move(new_solution), child_solution.start(), child_solution.end(), &new_propagated_state);
750766
}
751767

752768
WrapperBasePrivate::WrapperBasePrivate(WrapperBase* me, const std::string& name)

core/src/stages/compute_ik.cpp

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -330,13 +330,13 @@ void ComputeIK::compute() {
330330
->getParentJointModel()
331331
->getDescendantLinkModels();
332332
if (colliding) {
333-
SubTrajectory solution;
333+
auto solution = std::make_shared<SubTrajectory>();
334334
generateCollisionMarkers(sandbox_state, appender, links_to_visualize);
335-
std::copy(failure_markers.begin(), failure_markers.end(), std::back_inserter(solution.markers()));
336-
solution.markAsFailure();
335+
std::copy(failure_markers.begin(), failure_markers.end(), std::back_inserter(solution->markers()));
336+
solution->markAsFailure();
337337
// TODO: visualize collisions
338-
solution.setComment(s.comment() + " eef in collision: " + listCollisionPairs(collisions.contacts, ", "));
339-
spawn(InterfaceState(sandbox_scene), std::move(solution));
338+
solution->setComment(s.comment() + " eef in collision: " + listCollisionPairs(collisions.contacts, ", "));
339+
liftModifiedSolution(solution, InterfaceState(sandbox_scene), s);
340340
return;
341341
} else
342342
generateVisualMarkers(sandbox_state, appender, links_to_visualize);
@@ -389,18 +389,18 @@ void ComputeIK::compute() {
389389
for (size_t i = previous; i != ik_solutions.size(); ++i) {
390390
// create a new scene for each solution as they will have different robot states
391391
planning_scene::PlanningScenePtr scene = s.start()->scene()->diff();
392-
SubTrajectory solution;
393-
solution.setComment(s.comment());
392+
auto solution = std::make_shared<SubTrajectory>();
393+
solution->setComment(s.comment());
394394

395395
// frames at target pose and ik frame
396-
rviz_marker_tools::appendFrame(solution.markers(), target_pose_msg, 0.1, "ik frame");
397-
rviz_marker_tools::appendFrame(solution.markers(), ik_pose_msg, 0.1, "ik frame");
396+
rviz_marker_tools::appendFrame(solution->markers(), target_pose_msg, 0.1, "ik frame");
397+
rviz_marker_tools::appendFrame(solution->markers(), ik_pose_msg, 0.1, "ik frame");
398398

399399
if (succeeded && i + 1 == ik_solutions.size())
400400
// compute cost as distance to compare_pose
401-
solution.setCost(s.cost() + jmg->distance(ik_solutions.back().data(), compare_pose.data()));
401+
solution->setCost(s.cost() + jmg->distance(ik_solutions.back().data(), compare_pose.data()));
402402
else // found an IK solution, but this was not valid
403-
solution.markAsFailure();
403+
solution->markAsFailure();
404404

405405
// set scene's robot state
406406
robot_state::RobotState& robot_state = scene->getCurrentStateNonConst();
@@ -409,7 +409,7 @@ void ComputeIK::compute() {
409409

410410
InterfaceState state(scene);
411411
forwardProperties(*s.start(), state);
412-
spawn(std::move(state), std::move(solution));
412+
liftModifiedSolution(solution, std::move(state), s);
413413
}
414414

415415
// TODO: magic constant should be a property instead ("current_seed_only", or equivalent)
@@ -421,15 +421,15 @@ void ComputeIK::compute() {
421421

422422
if (ik_solutions.empty()) { // failed to find any solution
423423
planning_scene::PlanningScenePtr scene = s.start()->scene()->diff();
424-
SubTrajectory solution;
424+
auto solution = std::make_shared<SubTrajectory>();
425425

426-
solution.markAsFailure();
427-
solution.setComment(s.comment() + " no IK found");
426+
solution->markAsFailure();
427+
solution->setComment(s.comment() + " no IK found");
428428

429429
// ik target link placement
430-
std::copy(failure_markers.begin(), failure_markers.end(), std::back_inserter(solution.markers()));
430+
std::copy(failure_markers.begin(), failure_markers.end(), std::back_inserter(solution->markers()));
431431

432-
spawn(InterfaceState(scene), std::move(solution));
432+
liftModifiedSolution(solution, InterfaceState(scene), s);
433433
}
434434
}
435435
} // namespace stages

0 commit comments

Comments
 (0)