00001 00008 #ifndef MIN_JERK_TRAJECTORY_FACTORY_H 00009 #define MIN_JERK_TRAJECTORY_FACTORY_H 00010 00011 #include <robodyn_controllers/TrajectoryFactory.h> 00012 00013 class MinJerkJointTrajectoryFactory : public JointTrajectoryFactory<> 00014 { 00015 public: 00016 MinJerkJointTrajectoryFactory() : JointTrajectoryFactory<>() {} 00017 virtual ~MinJerkJointTrajectoryFactory() {} 00018 00028 virtual boost::shared_ptr<JointTrajectory> getTrajectory(const KDL::JntArrayAcc& startPose, 00029 const KDL::JntArrayAcc& goalPose, double durationTarget = -1.) const; 00030 }; 00031 00032 class MinJerkCartesianTrajectoryFactory : public CartesianTrajectoryFactory<> 00033 { 00034 public: 00035 MinJerkCartesianTrajectoryFactory() : CartesianTrajectoryFactory<>() {} 00036 virtual ~MinJerkCartesianTrajectoryFactory() {} 00037 00047 virtual boost::shared_ptr<CartesianTrajectory> getTrajectory(const KDL::FrameAcc& startPose, 00048 const KDL::FrameAcc& goalPose, double timeToFinish = -1.) const; 00049 }; 00050 00051 class MinJerkSynchedCartesianTrajectoryFactory : public SynchedCartesianTrajectoryFactory 00052 { 00053 public: 00054 MinJerkSynchedCartesianTrajectoryFactory() : SynchedCartesianTrajectoryFactory() {} 00055 virtual ~MinJerkSynchedCartesianTrajectoryFactory() {} 00056 00066 virtual boost::shared_ptr<SynchedCartesianTrajectory> getTrajectory(const std::vector<KDL::FrameAcc>& startPoses, 00067 const std::vector<KDL::FrameAcc>& goalPoses, double timeToFinish = -1.) const; 00068 }; 00069 00070 #endif