00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #ifndef __N_AXES_CONTROLLER_POSVELACC_H__
00019 #define __N_AXES_CONTROLLER_POSVELACC_H__
00020
00021 #include <rtt/RTT.hpp>
00022 #include <rtt/TaskContext.hpp>
00023 #include <rtt/Properties.hpp>
00024 #include <rtt/TimeService.hpp>
00025 #include <rtt/Ports.hpp>
00026
00027 #include <ocl/OCL.hpp>
00028
00029 namespace OCL
00030 {
00046 class nAxesControllerPosVelAcc : public RTT::TaskContext
00047 {
00048 public:
00055 nAxesControllerPosVelAcc(std::string name);
00056 virtual ~nAxesControllerPosVelAcc();
00067 virtual bool configureHook();
00075 virtual bool startHook();
00080 virtual void updateHook();
00081 virtual void stopHook();
00082
00083 private:
00084 void resetAll();
00085 void resetAxis(int axis);
00086
00087 unsigned int num_axes;
00088
00089 std::vector<double> p_m, p_d, p_d_prev,
00090 v_m,v_d, v_d_prev, a_d, a_out, Kp, Kv;
00091 protected:
00093 RTT::Method<void(void)> reset_all_mtd;
00099 RTT::Method<void(int)> resetAxis_mtd;
00100
00102 RTT::ReadDataPort< std::vector<double> > p_m_port;
00104 RTT::ReadDataPort< std::vector<double> > v_m_port;
00106 RTT::DataPort< std::vector<double> > p_d_port;
00108 RTT::DataPort< std::vector<double> > v_d_port;
00110 RTT::DataPort< std::vector<double> > a_d_port;
00112 RTT::WriteDataPort< std::vector<double> > a_out_port;
00114 RTT::Property< std::vector<double> > Kp_prop;
00116 RTT::Property< std::vector<double> > Kv_prop;
00118 RTT::Property<unsigned int> num_axes_prop;
00120 RTT::Property<bool> use_ad,use_vd,use_pd;
00123 RTT::Property<bool> avoid_drift;
00126 RTT::Property<bool> differentiate;
00127
00128
00129 private:
00130 std::vector<bool> is_initialized;
00131 std::vector<RTT::TimeService::ticks> time_begin;
00132 std::vector<RTT::TimeService::Seconds> time_difference;
00133
00134
00135 };
00136 }
00137
00138 #endif // __N_AXES_CONTROLLER_ACC_H__