#include <MinJerkTrajectoryFactory.h>
Public Member Functions | |
virtual boost::shared_ptr < JointTrajectory > | getTrajectory (const KDL::JntArrayAcc &startPose, const KDL::JntArrayAcc &goalPose, double durationTarget=-1.) const |
getTrajectory produces a trajectory object from the inputs | |
MinJerkJointTrajectoryFactory () | |
virtual | ~MinJerkJointTrajectoryFactory () |
Definition at line 13 of file MinJerkTrajectoryFactory.h.
Definition at line 16 of file MinJerkTrajectoryFactory.h.
virtual MinJerkJointTrajectoryFactory::~MinJerkJointTrajectoryFactory | ( | ) | [inline, virtual] |
Definition at line 17 of file MinJerkTrajectoryFactory.h.
boost::shared_ptr< JointTrajectory > MinJerkJointTrajectoryFactory::getTrajectory | ( | const KDL::JntArrayAcc & | startPose, |
const KDL::JntArrayAcc & | goalPose, | ||
double | durationTarget = -1. |
||
) | const [virtual] |
getTrajectory produces a trajectory object from the inputs
startPose | start joint positions |
goalPose | goal joint positions |
timeToFinish | time to execute move |
Derived classes should implement a trajectory generation that produces equally spaced (by timeStep) points along the path without exceeding the velocity limits. If timeToFinish is larger than the time required to satisfy velocity limits, the trajectory should take that long to finish.
Definition at line 5 of file MinJerkTrajectoryFactory.cpp.