00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #ifndef __CARTESIAN_VEL_CONTROLLER_H__
00022 #define __CARTESIAN_VEL_CONTROLLER_H__
00023
00024 #include <rtt/RTT.hpp>
00025
00026 #include <rtt/TaskContext.hpp>
00027 #include <rtt/TimeService.hpp>
00028 #include <rtt/Properties.hpp>
00029 #include <rtt/Ports.hpp>
00030
00031 #include <kdl/kdl.hpp>
00032 #include <kdl/frames.hpp>
00033
00034 #include <ocl/OCL.hpp>
00035
00036 namespace OCL
00037 {
00046 class CartesianControllerVel : public RTT::TaskContext
00047 {
00048
00049 public:
00055 CartesianControllerVel(std::string name);
00056 virtual ~CartesianControllerVel();
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 KDL::Frame _position_meas_local, _position_integrated;
00066 KDL::Twist _velocity_out_local, _velocity_desi_local, _velocity_feedback;
00067 std::vector<double> _gain_local;
00068
00069 RTT::TimeService::ticks _time_begin;
00070 bool _is_initialized;
00071
00072 protected:
00075 RTT::ReadDataPort< KDL::Frame > _position_meas;
00079 RTT::DataPort< KDL::Twist > _velocity_desi;
00083 RTT::WriteDataPort< KDL::Twist > _velocity_out;
00085 RTT::Property< std::vector<double> > _controller_gain;
00086
00087 };
00088 }
00089 #endif // __N_AXES_CARTESIAN_VEL_CONTROLLER_H__