mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
MoveTo/MoveRelative: report failure on invalid trajectories (#107)
This commit is contained in:
parent
6764b2a9ca
commit
1ba4bc4508
@ -290,8 +290,9 @@ bool MoveRelative::compute(const InterfaceState& state, planning_scene::Planning
|
||||
solution.setTrajectory(robot_trajectory);
|
||||
if (!success)
|
||||
solution.markAsFailure();
|
||||
return true;
|
||||
}
|
||||
return true;
|
||||
return false;
|
||||
}
|
||||
|
||||
void MoveRelative::computeForward(const InterfaceState& from) {
|
||||
|
||||
@ -246,12 +246,12 @@ bool MoveTo::compute(const InterfaceState& state, planning_scene::PlanningSceneP
|
||||
|
||||
if (!success)
|
||||
solution.markAsFailure();
|
||||
|
||||
return true;
|
||||
}
|
||||
return true;
|
||||
return false;
|
||||
}
|
||||
|
||||
// -1 TODO: move these as default implementation to PropagateEitherWay?
|
||||
// Essentially, here compute() is a class-specific worker function
|
||||
void MoveTo::computeForward(const InterfaceState& from) {
|
||||
planning_scene::PlanningScenePtr to;
|
||||
SubTrajectory trajectory;
|
||||
|
||||
Loading…
Reference in New Issue
Block a user