33 void DesignerTrajectoryManager::ManipulationInterval::addFirstUserWaypoint(
UserWaypointPtr uw)
35 userWaypointsList.push_back(uw);
40 userWaypointsList.push_front(uw);
41 transitionsList.push_front(t);
47 userWaypointsList.push_back(uw);
48 transitionsList.push_back(t);
52 void DesignerTrajectoryManager::ManipulationInterval::addBreakpointIndex(
int index)
54 breakpointIndicesSet.insert(
index);
57 void DesignerTrajectoryManager::ManipulationInterval::finishSearch()
60 userWaypoints.reserve(userWaypointsList.size());
62 userWaypointsList.begin(),
63 userWaypointsList.end(),
64 std::back_inserter(userWaypoints));
67 transitions.reserve(transitionsList.size());
69 transitionsList.begin(),
70 transitionsList.end(),
71 std::back_inserter(transitions));
74 breakpointIndices.reserve(breakpointIndicesSet.size());
76 breakpointIndicesSet.begin(),
77 breakpointIndicesSet.end(),
78 std::back_inserter(breakpointIndices)
82 UserWaypointPtr DesignerTrajectoryManager::ManipulationInterval::getUserWaypointByRealIndex(
85 if (i - lowerIntervalLimit < userWaypoints.size())
87 return userWaypoints[i - lowerIntervalLimit];
92 throw OutOfRangeException();
97 UserWaypointPtr DesignerTrajectoryManager::ManipulationInterval::getUserWaypointByZeroBasedIndex(
100 if (i < userWaypoints.size())
102 return userWaypoints[i];
107 throw OutOfRangeException();
111 TransitionPtr DesignerTrajectoryManager::ManipulationInterval::getTransitionByRealIndex(
112 unsigned int i)
const
114 if (i - lowerIntervalLimit < transitions.size())
116 return transitions[i - lowerIntervalLimit];
121 throw OutOfRangeException();
125 TransitionPtr DesignerTrajectoryManager::ManipulationInterval::getTransitionByZeroBasedIndex(
126 unsigned int i)
const
128 if (i < transitions.size())
130 return transitions[i];
135 throw OutOfRangeException();
139 std::vector<std::vector<double>> DesignerTrajectoryManager::ManipulationInterval::
140 getUserWaypointsIKSolutions(
141 std::vector<std::vector<double>>& ikSolutions,
142 unsigned int intervalStart,
143 unsigned int intervalEnd)
145 std::vector<std::vector<double>> result;
146 for (
unsigned int& newIndex : newIndexOfUserWaypoint)
148 if (newIndex < intervalStart)
152 if (newIndex > intervalEnd)
157 result.push_back(ikSolutions[newIndex]);
162 void DesignerTrajectoryManager::ManipulationInterval::applyJointAnglesOfUserWaypoints(
163 std::vector<std::vector<double>> ikSolution)
165 std::vector<std::vector<double>>
jointAngles = getUserWaypointsIKSolutions(
167 newIndexOfUserWaypoint[0],
168 newIndexOfUserWaypoint[userWaypoints.size() - 1]);
181 void DesignerTrajectoryManager::saveState()
184 if (mementos.currentMemento < mementos.mementoList.size() - 1)
186 mementos.mementoList.resize(mementos.currentMemento + 1);
189 if (designerTrajectory)
191 mementos.mementoList.push_back(std::shared_ptr<DesignerTrajectory>(
196 mementos.mementoList.push_back(
nullptr);
201 if (mementos.mementoList.size() > MEMENTO_MAX)
203 mementos.mementoList.pop_front();
207 mementos.currentMemento++;
211 DesignerTrajectoryManager::ManipulationInterval
212 DesignerTrajectoryManager::calculateManipulationInterval(
unsigned int manipulationIndex)
215 ManipulationInterval mi;
218 mi.lowerIntervalLimit = manipulationIndex;
219 mi.upperIntervalLimit = manipulationIndex;
222 mi.addFirstUserWaypoint(
dt->getUserWaypoint(manipulationIndex));
225 if (
dt->getUserWaypoint(manipulationIndex)->getIsTimeOptimalBreakpoint())
227 mi.addBreakpointIndex(manipulationIndex);
231 for (
unsigned int i = manipulationIndex + 1; i <
dt->getNrOfUserWaypoints(); i++)
235 mi.pushBack(tmpUwp, tmpTrans);
237 if (tmpUwp->getIsTimeOptimalBreakpoint())
239 mi.addBreakpointIndex(i);
252 for (
unsigned int i = manipulationIndex - 1; i !=
static_cast<unsigned>(-1); i--)
256 mi.pushFront(tmpUwp, tmpTrans);
258 if (tmpUwp->getIsTimeOptimalBreakpoint())
260 mi.addBreakpointIndex(i);
273 mi.addBreakpointIndex(mi.lowerIntervalLimit);
274 mi.addBreakpointIndex(mi.upperIntervalLimit);
280 std::vector<AbstractInterpolationPtr> DesignerTrajectoryManager::getInterpolationObjects(
281 ManipulationInterval& mi)
283 std::vector<PoseBasePtr> poses;
286 poses.push_back(uwp->getPose());
289 std::vector<InterpolationType> interpolationTypes;
292 interpolationTypes.push_back(tp->getInterpolationType());
298 void DesignerTrajectoryManager::calculateInterpolatedPoints(
299 std::vector<AbstractInterpolationPtr> interpolationObjects,
301 ManipulationInterval& mi)
310 for (
unsigned int i = 0; i < mi.transitions.size(); i++)
312 std::vector<double> timestamps;
316 TransitionPtr tmpTransition = mi.getTransitionByZeroBasedIndex(i);
320 unsigned int totalFrameCount = tmpTransition->getTimeOptimalDuration() * fps;
322 if (totalFrameCount == 0)
324 totalFrameCount = DEFAULT_FRAME_COUNT;
327 if (totalFrameCount > 1)
330 double increment = 1.0 / (totalFrameCount - 1);
334 for (
unsigned int k = 0; k < totalFrameCount; k++)
336 timestamps.push_back(k * increment);
341 timestamps.push_back(0.0);
342 timestamps.push_back(1.0);
346 std::vector<PoseBasePtr> tmpInterpolatedPositions;
347 for (
double timestamp : timestamps)
350 tmpInterpolatedPositions.push_back(interpolationObjects[i]->getPoseAt(timestamp));
353 mi.interpolatedTransitions.push_back(tmpInterpolatedPositions);
354 tmpInterpolatedPositions.clear();
362 bool DesignerTrajectoryManager::checkTransitionReachability(
363 ManipulationInterval& mi,
unsigned int transitionIndex)
365 for (PoseBasePtr pose : mi.interpolatedTransitions[transitionIndex])
380 std::vector<std::vector<double>> DesignerTrajectoryManager::calculateIKSolutions(
381 ManipulationInterval& mi)
384 std::vector<std::vector<double>> ikSolutions;
385 ikSolutions.push_back(mi.userWaypoints[0]->getJointAngles());
388 mi.newIndexOfUserWaypoint.push_back(0);
391 std::vector<InsertTransition> mpInserts;
393 for (
unsigned int transitionIndex = 0;
394 transitionIndex < mi.interpolatedTransitions.size();
397 if (!checkTransitionReachability(mi, transitionIndex))
400 InsertTransition mpInsert;
401 mpInsert.transitionIndex = transitionIndex;
402 mpInsert.insertionIndex = ikSolutions.size() - 1;
403 mpInserts.push_back(mpInsert);
406 std::vector<double> start
407 = {ikSolutions.back()};
409 std::vector<PoseBasePtr> destinations
410 = {mi.interpolatedTransitions[transitionIndex].back()};
412 std::vector<VirtualRobot::IKSolver::CartesianSelection> selections
413 = {mi.userWaypoints[transitionIndex + 1]->getIKSelection()};
415 std::vector<std::vector<double>> tmpIkSolutions = kinSolver->solveRecursiveIKRelative(
422 ikSolutions.insert(ikSolutions.end(), tmpIkSolutions.begin(), tmpIkSolutions.end());
427 mi.newIndexOfUserWaypoint.push_back(-1);
435 std::vector<double> start
436 = {ikSolutions.back()};
439 std::vector<PoseBasePtr> destinations(
440 mi.interpolatedTransitions[transitionIndex].begin() + 1,
441 mi.interpolatedTransitions[transitionIndex].end());
444 std::vector<VirtualRobot::IKSolver::CartesianSelection> selections;
447 for (
unsigned int i = 1; i < destinations.size(); i++)
449 selections.push_back(mi.userWaypoints[transitionIndex + 1]->getIKSelection());
453 selections.push_back(mi.userWaypoints[transitionIndex + 1]->getIKSelection());
456 std::vector<std::vector<double>> tmpIkSolutions = kinSolver->solveRecursiveIKRelative(
467 ikSolutions.insert(ikSolutions.end(), tmpIkSolutions.begin(), tmpIkSolutions.end());
469 mi.newIndexOfUserWaypoint.push_back(ikSolutions.size() - 1);
474 std::vector<TimedTrajectory> DesignerTrajectoryManager::calculateTimeOptimalTrajectories(
475 std::vector<std::vector<double>> ikSolutions,
476 ManipulationInterval& mi)
478 std::vector<TimedTrajectory> result;
480 for (
unsigned int i = 0; i < mi.breakpointIndices.size() - 1; i++)
485 int intervalStart = mi.breakpointIndices[i];
486 int intervalEnd = mi.breakpointIndices[i + 1];
487 std::vector<std::vector<double>> ikSolutionsInterval(
488 ikSolutions.begin() + mi.newIndexOfUserWaypoint[intervalStart],
489 ikSolutions.begin() + 1 + mi.newIndexOfUserWaypoint[intervalEnd]);
497 std::vector<std::vector<double>> userWaypointsIKSolution
498 = mi.getUserWaypointsIKSolutions(
500 mi.newIndexOfUserWaypoint[intervalStart],
501 mi.newIndexOfUserWaypoint[intervalEnd]);
506 userWaypointsIKSolution,
516 if (mementos.currentMemento != 0)
518 if (*(std::next(mementos.mementoList.begin(), mementos.currentMemento - 1)))
521 mementos.currentMemento - 1)))));
522 isInitialized =
true;
526 isInitialized =
false;
528 mementos.currentMemento--;
539 if (mementos.currentMemento < mementos.mementoList.size() - 1)
541 if (*std::next(mementos.mementoList.begin(), mementos.currentMemento + 1))
544 mementos.currentMemento + 1)))));
548 isInitialized =
false;
551 mementos.currentMemento++;
562 return isInitialized;
565 void DesignerTrajectoryManager::theUniversalMethod(
unsigned int index)
567 if (designerTrajectory->getNrOfUserWaypoints() > 1)
570 ManipulationInterval mi = calculateManipulationInterval(
index);
573 std::vector<PoseBasePtr> poses;
574 std::vector<PoseBasePtr> posesBackup;
577 std::vector<VirtualRobot::IKSolver::CartesianSelection> selections;
578 std::vector<VirtualRobot::IKSolver::CartesianSelection> selectionsBackup;
582 poses.push_back(uwp->getPose());
583 posesBackup.push_back(PoseBasePtr(
new Pose(
Pose(uwp->getPose()->position, uwp->getPose()->orientation).toEigen())));
584 selections.push_back(uwp->getIKSelection());
585 selectionsBackup.push_back(uwp->getIKSelection());
593 std::vector<InterpolationType> interpolations;
596 interpolations.push_back(trans->getInterpolationType());
601 uwp->setPose(poses[count]);
602 uwp->setIKSelection(selections[count]);
606 calculateInterpolatedPoints(
616 std::vector<std::vector<double>> ikSolutions = calculateIKSolutions(mi);
621 uwp->setIKSelection(selectionsBackup[count]);
622 uwp->setPose(posesBackup[count]);
627 mi.applyJointAnglesOfUserWaypoints(ikSolutions);
630 std::vector<TimedTrajectory> timedTrajectories = calculateTimeOptimalTrajectories(
636 if (mi.lowerIntervalLimit != 0)
639 for (
unsigned int i = mi.lowerIntervalLimit - 1; i > 0; i--)
641 if (designerTrajectory->getUserWaypoint(i)->getIsTimeOptimalBreakpoint())
648 if (mi.upperIntervalLimit != designerTrajectory->getNrOfUserWaypoints() - 1)
651 for (
unsigned int i = mi.upperIntervalLimit + 1; i < designerTrajectory->
652 getNrOfUserWaypoints() - 1; i++)
658 std::vector<TrajectoryPtr> InterBreakPointTrajectories =
659 designerTrajectory->getInterBreakpointTrajectories();
660 std::vector<TrajectoryPtr> newInterBreakPointTrajectories;
661 newInterBreakPointTrajectories.insert(newInterBreakPointTrajectories.end(),
662 InterBreakPointTrajectories.begin(),
663 InterBreakPointTrajectories.begin() +
670 newInterBreakPointTrajectories.push_back(traj);
673 newInterBreakPointTrajectories.insert(newInterBreakPointTrajectories.end(),
674 InterBreakPointTrajectories.end() - countAfter,
675 InterBreakPointTrajectories.end());
676 designerTrajectory->setInterBreakpointTrajectories(newInterBreakPointTrajectories);
681 TrajectoryPtr traj = designerTrajectory ->getTimeOptimalTrajectory();
682 std::vector<double> timestamps = traj->getTimestamps();
683 unsigned int trajCount = 0;
686 while (trajCount < timestamps.size() &&
687 designerTrajectory->getUserWaypoint(mi.breakpointIndices[0])->getTimeOptimalTimestamp()
688 > timestamps[trajCount])
693 for (
unsigned int t = 0; t < timedTrajectories.size(); t++)
696 std::vector<double> timedUserWaypoints = timedTrajectories[t].getUserPoints();
698 if (timedUserWaypoints.size() == 0)
700 throw InvalidArgumentException();
703 unsigned int count = 0;
707 for (
unsigned int i = mi.breakpointIndices[t]; i < mi.breakpointIndices[t + 1]; i++)
711 setTimeOptimalDuration(timedUserWaypoints[count + 1] -
712 timedUserWaypoints[count]);
718 for (
unsigned int i = mi.breakpointIndices[t]; i < mi.breakpointIndices[t + 1]; i++)
722 unsigned int trajCountEnd = trajCount + 1;
723 std::vector<double> newTimestamps = {0.0};
724 std::vector<std::vector<double>> newTrajData;
726 for (
unsigned int dim = 0; dim < traj->dim(); dim++)
728 newTrajData.push_back({traj->getState(timestamps[trajCount], dim)});
732 while (trajCountEnd < timestamps.size() && timestamps[trajCountEnd] < end->getTimeOptimalTimestamp())
734 newTimestamps.push_back(timestamps[trajCountEnd] - timestamps[trajCount]);
735 for (
unsigned int dim = 0; dim < traj->dim(); dim++)
738 newTrajData[dim].push_back(traj->getState(timestamps[trajCountEnd], dim));
742 trajCount = trajCountEnd;
744 trans->setTrajectory(newTraj);
750 for (
unsigned int i = mi.breakpointIndices.back();
751 i <= designerTrajectory->getNrOfUserWaypoints() - 2; i++)
755 double time = designerTrajectory->getTransition(i)->getTimeOptimalDuration();
756 designerTrajectory->getTransition(i)->setTimeOptimalDuration(time);
762 for (
unsigned int i = 0; i < designerTrajectory->getNrOfUserWaypoints() - 2; i++)
764 double time = designerTrajectory->getTransition(i)->getStart()->getUserTimestamp()
765 + designerTrajectory->getTransition(i)->getUserDuration();
766 designerTrajectory->getTransition(i)->getEnd()->setUserTimestamp(time);
772 std::vector<double> DesignerTrajectoryManager::getNewIkSolutionOfFirstPoint(PoseBasePtr oldStart, PoseBasePtr newStart, std::vector<double> jointAnglesOldStart)
776 std::vector<PoseBasePtr> poses;
777 std::vector<VirtualRobot::IKSolver::CartesianSelection> selections;
781 for (
double i = 1; i < DEFAULT_FRAME_COUNT - 1; i = i + 1.0)
783 poses.push_back(current->getPoseAt(i / DEFAULT_FRAME_COUNT));
787 poses.push_back(newStart);
788 selections.push_back(VirtualRobot::IKSolver::CartesianSelection::All);
789 std::vector<std::vector<double>> ikSolutions = kinSolver->solveRecursiveIKRelative(rns, jointAnglesOldStart, poses, selections);
791 return ikSolutions.back();
801 environment->getScene(),
802 environment->getRobot())),
803 environment(environment)
805 rns = environment->getRobot()->getRobotNodeSet(rnsName);
815 PoseBasePtr pb = kinSolver->doForwardKinematic(rns,
jointAngles);
816 Pose pose =
Pose(pb->position, pb->orientation);
817 pb = PoseBasePtr(
new Pose(rns->getKinematicRoot()->toLocalCoordinateSystem(pose.
toEigen())));
827 if (mementos.mementoList.size() != 0)
837 isInitialized =
true;
848 designerTrajectory->addLastUserWaypoint(newPoint);
849 theUniversalMethod(designerTrajectory->getNrOfUserWaypoints() - 1);
853 throw NotInitializedException(
"Manager is not intialized",
"Manager");
867 designerTrajectory->insertUserWaypoint(newPoint,
index);
868 theUniversalMethod(
index);
872 PoseBasePtr oldStart = designerTrajectory->getUserWaypoint(0)->getPose();
873 std::vector<double>
jointAngles = getNewIkSolutionOfFirstPoint(oldStart, pb, designerTrajectory->getUserWaypoint(0)->getJointAngles());
879 designerTrajectory->insertUserWaypoint(newPoint,
index);
880 designerTrajectory->getUserWaypoint(0)->setJointAngles(
jointAngles);
882 theUniversalMethod(
index);
887 throw NotInitializedException(
"Manager is not intialized",
"Manager");
899 designerTrajectory->getUserWaypoint(
index)->setPose(pb);
903 std::vector<double> newJointAngles;
904 if (designerTrajectory->getNrOfUserWaypoints() > 1)
906 newJointAngles = getNewIkSolutionOfFirstPoint(
907 designerTrajectory->getUserWaypoint(1)->getPose(), pb,
908 designerTrajectory->getUserWaypoint(1)->getJointAngles());
909 if (newJointAngles.size() == 0)
913 designerTrajectory->getUserWaypoint(0)->setPose(pb);
914 designerTrajectory->getUserWaypoint(0)->setJointAngles(newJointAngles);
919 newJointAngles = getNewIkSolutionOfFirstPoint(
920 designerTrajectory->getUserWaypoint(0)->getPose(),
922 designerTrajectory->getUserWaypoint(0)->getJointAngles());
923 if (newJointAngles.size() == 0)
928 uwpTmp->setJointAngles(newJointAngles);
929 uwpTmp->setIKSelection(designerTrajectory->getUserWaypoint(0)->getIKSelection());
930 uwpTmp->setIsTimeOptimalBreakpoint(
931 designerTrajectory->getUserWaypoint(0)->getIsTimeOptimalBreakpoint());
933 designerTrajectory = dtTmp;
936 theUniversalMethod(
index);
940 throw NotInitializedException(
"Manager is not intialized",
"Manager");
951 designerTrajectory->getUserWaypoint(
index)->setIKSelection(ikSelection);
952 theUniversalMethod(
index);
956 throw NotInitializedException(
"Manager is not intialized",
"Manager");
967 if (designerTrajectory->getNrOfUserWaypoints() == 1)
969 isInitialized =
false;
970 designerTrajectory =
nullptr;
975 designerTrajectory->deleteUserWaypoint(
index);
980 designerTrajectory->getUserWaypoint(0)->setTimeOptimalTimestamp(0);
981 designerTrajectory->getUserWaypoint(0)->setUserTimestamp(0);
985 if (designerTrajectory->getNrOfUserWaypoints() == 1)
992 if (
index == designerTrajectory->getNrOfUserWaypoints())
994 theUniversalMethod(
index - 1);
998 theUniversalMethod(
index);
1004 throw NotInitializedException(
"Manager is not intialized",
"Manager");
1015 designerTrajectory->getTransition(
index)->setInterpolationType(it);
1016 theUniversalMethod(
index);
1020 throw NotInitializedException(
"Manager is not intialized",
"Manager");
1031 designerTrajectory->getUserWaypoint(
index)->setIsTimeOptimalBreakpoint(b);
1032 theUniversalMethod(
index);
1036 throw NotInitializedException(
"Manager is not intialized",
"Manager");
1047 designerTrajectory->getTransition(
index)->setUserDuration(duration);
1049 for (
unsigned int i =
index + 1; i < designerTrajectory->getNrOfUserWaypoints() - 1; i++)
1052 trans->setUserDuration(trans->getUserDuration());
1059 throw NotInitializedException(
"Manager is not intialized",
"Manager");
1069 mementos.currentMemento))));
1080 if (newDesignerTrajectory->getNrOfUserWaypoints() > 1 && newDesignerTrajectory->getRns()->getName() == rns->getName())
1082 TrajectoryPtr trajectory = newDesignerTrajectory->getTimeOptimalTrajectory();
1085 for (
unsigned int i = 0; i < newDesignerTrajectory->getNrOfUserWaypoints() - 1; i++)
1087 TransitionPtr trans = newDesignerTrajectory->getTransition(i);
1088 double transBeginTime = trans->getStart()->getTimeOptimalTimestamp();
1089 double transEndTime = trans->getEnd()->getTimeOptimalTimestamp();
1090 TrajectoryPtr traj = trajectory->getPart(transBeginTime, transEndTime, 2);
1094 std::vector<std::vector<double>> nodeData;
1095 for (
unsigned int dim = 0; dim < traj->dim(); dim++)
1097 nodeData.push_back(traj->getDimensionData(dim));
1099 std::vector<double> newTimestamps = {0.0};
1100 std::vector<double> oldTimestamps = traj->getTimestamps();
1101 for (
unsigned int j = 1; j < oldTimestamps.size(); j++)
1103 if (oldTimestamps[j] - transBeginTime >= 0)
1105 newTimestamps.push_back(oldTimestamps[j] - transBeginTime);
1109 newTimestamps.push_back(0);
1114 trans->setTrajectory(shiftedTraj);
1116 designerTrajectory = newDesignerTrajectory;
1118 if (mementos.mementoList.size() != 0)
1127 isInitialized =
true;
1135 return mementos.currentMemento > 0;
1140 if (mementos.mementoList.size() != 0 && mementos.currentMemento < mementos.mementoList.size() - 1)