00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #ifndef __CARTESIAN_POS_CONTROLLER_H__
00022 #define __CARTESIAN_POS_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 CartesianControllerPos : public RTT::TaskContext
00046 {
00047 public:
00054 CartesianControllerPos(std::string name);
00055
00056 virtual ~CartesianControllerPos();
00057
00058 virtual bool configureHook();
00059 virtual bool startHook();
00060 virtual void updateHook();
00061 virtual void stopHook();
00062 virtual void cleanupHook();
00063
00064 private:
00065
00066 KDL::Frame _position_meas_local, _position_desi_local;
00067 KDL::Twist _velocity_out_local;
00068 std::vector<double> _gain_local;
00069
00070 protected:
00073 RTT::ReadDataPort< KDL::Frame > _position_meas;
00076 RTT::ReadDataPort< KDL::Frame > _position_desi;
00080 RTT::WriteDataPort< KDL::Twist > _velocity_out;
00082 RTT::Property< std::vector<double> > _controller_gain;
00083
00084 };
00085 }
00086
00087 #endif // __N_AXES_CARTESIAN_POS_CONTROLLER_H__