00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #ifndef __CARTESIAN_POS_VEL_CONTROLLER_H__
00022 #define __CARTESIAN_POS_VEL_CONTROLLER_H__
00023
00024 #include <rtt/RTT.hpp>
00025
00026 #include <rtt/TaskContext.hpp>
00027 #include <rtt/Properties.hpp>
00028 #include <rtt/Ports.hpp>
00029
00030 #include <kdl/kdl.hpp>
00031 #include <kdl/frames.hpp>
00032
00033 #include <ocl/OCL.hpp>
00034
00035 namespace OCL
00036 {
00045 class CartesianControllerPosVel : public RTT::TaskContext
00046 {
00047 public:
00054 CartesianControllerPosVel(std::string name);
00055 virtual ~CartesianControllerPosVel();
00056
00057 virtual bool configureHook();
00058 virtual bool startHook();
00059 virtual void updateHook();
00060 virtual void stopHook();
00061 virtual void cleanupHook();
00062
00063 private:
00064 KDL::Frame _position_meas_local, _position_desi_local;
00065 KDL::Twist _velocity_out_local, _velocity_desi_local, _velocity_feedback;
00066 std::vector<double> _gain_local;
00067
00068 protected:
00071 RTT::ReadDataPort< KDL::Frame > _position_meas;
00074 RTT::ReadDataPort< KDL::Frame > _position_desi;
00078 RTT::ReadDataPort< KDL::Twist > _velocity_desi;
00082 RTT::WriteDataPort< KDL::Twist > _velocity_out;
00084 RTT::Property< std::vector<double> > _controller_gain;
00085
00086 };
00087 }
00088 #endif // __N_AXES_CARTESIAN_POS_VEL_CONTROLLER_H__