00001 00008 #ifndef TRAP_VEL_TRAJECTORY_FACTORY_H 00009 #define TRAP_VEL_TRAJECTORY_FACTORY_H 00010 00011 #include "robodyn_controllers/TrajectoryFactory.h" 00012 #include "robodyn_controllers/TrapezoidalVelocityTrajectory.h" 00013 #include "nasa_common_logging/Logger.h" 00014 00015 class TrapezoidalVelocityJointTrajectoryFactory : public JointTrajectoryFactory<> 00016 { 00017 public: 00018 TrapezoidalVelocityJointTrajectoryFactory() : JointTrajectoryFactory<>() {} 00019 virtual ~TrapezoidalVelocityJointTrajectoryFactory() {} 00020 00030 virtual boost::shared_ptr<JointTrajectory> getTrajectory(const KDL::JntArrayAcc& startPose, 00031 const KDL::JntArrayAcc& goalPose, double durationTarget = -1.) const; 00032 }; 00033 00034 class TrapezoidalVelocityCartesianTrajectoryFactory : public CartesianTrajectoryFactory<> 00035 { 00036 public: 00037 TrapezoidalVelocityCartesianTrajectoryFactory() : CartesianTrajectoryFactory<>() {} 00038 virtual ~TrapezoidalVelocityCartesianTrajectoryFactory() {} 00039 00049 virtual boost::shared_ptr<CartesianTrajectory> getTrajectory(const KDL::FrameAcc& startPose, 00050 const KDL::FrameAcc& goalPose, double timeToFinish = -1.) const; 00051 }; 00052 00053 class TrapezoidalVelocitySynchedCartesianTrajectoryFactory : public SynchedCartesianTrajectoryFactory 00054 { 00055 public: 00056 TrapezoidalVelocitySynchedCartesianTrajectoryFactory() : SynchedCartesianTrajectoryFactory() {} 00057 virtual ~TrapezoidalVelocitySynchedCartesianTrajectoryFactory() {} 00058 00068 virtual boost::shared_ptr<SynchedCartesianTrajectory> getTrajectory(const std::vector<KDL::FrameAcc>& startPoses, 00069 const std::vector<KDL::FrameAcc>& goalPoses, double timeToFinish = -1.) const; 00070 }; 00071 00072 #endif