ForceTrajectory.h
Go to the documentation of this file.
00001 #ifndef FORCETRAJECTORY_H
00002 #define FORCETRAJECTORY_H
00003 #include "robodyn_controllers/TreeIkTrajectory.h"
00004 #include "robodyn_controllers/Cartesian_HybCntrl.h"
00005 #include "nasa_common_logging/Logger.h"
00006 
00007 class ForceTrajectory : public TreeIkTrajectory
00008 {
00009 public:
00010     ForceTrajectory();
00011     virtual ~ForceTrajectory() {}
00012 
00013     void setCartesianHybCntrl(boost::shared_ptr<Cartesian_HybCntrl> forceController_in)
00014     {
00015         forceController = forceController_in;
00016     }
00017 
00024     virtual void getPose(double time, KDL::JntArrayAcc& pose);
00025     void printFrame(std::string name, KDL::Frame frame);
00026 
00027 protected:
00028     boost::shared_ptr<Cartesian_HybCntrl> forceController;
00029     double lastTime;
00030     std::string logCategory;
00031 };
00032 
00033 #endif // FORCETRAJECTORY_H


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:53