00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef __CARTESIAN_VELOCITY_CONTROLLER_HPP__
00021 #define __CARTESIAN_VELOCITY_CONTROLLER_HPP__
00022
00023 #include <kdl/chain.hpp>
00024 #include <kdl/chainfksolver.hpp>
00025 #include <kdl/chainiksolver.hpp>
00026
00027 #include <rtt/TaskContext.hpp>
00028 #include <rtt/Ports.hpp>
00029
00030 #include <ocl/OCL.hpp>
00031
00032 namespace OCL
00033 {
00047 class CartesianVelocityController : public RTT::TaskContext
00048 {
00049 public:
00050 CartesianVelocityController(std::string name);
00051 ~CartesianVelocityController();
00052
00053 virtual bool configureHook();
00054 virtual bool startHook();
00055 virtual void updateHook();
00056 virtual void stopHook();
00057 virtual void cleanupHook();
00058
00059 private:
00060 KDL::Chain chain;
00061 KDL::ChainFkSolverPos* fksolver;
00062 KDL::ChainIkSolverVel* iksolver;
00063
00064 unsigned int nj;
00065
00066 KDL::JntArray *jointpositions,*jointvelocities;
00067 std::vector<double> naxesposition,naxesvelocities;
00068
00069 KDL::Twist cartvel;
00070 KDL::Frame cartpos;
00071
00072 RTT::DataPort<KDL::Frame> cartpos_port;
00073 RTT::DataPort<KDL::Twist> cartvel_port;
00074 RTT::DataPort<std::vector<double> > naxespos_port;
00075 RTT::DataPort<std::vector<double> > naxesvel_port;
00076
00077 RTT::Property<KDL::Chain> chain_prop;
00078 RTT::Property<KDL::Frame> toolframe;
00079
00080 bool kinematics_status;
00081
00082 };
00083 }
00084 #endif
00085
00086
00087