ModifiedServo.h
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #ifndef MODIFIEDSERVO_H
00011 #define MODIFIEDSERVO_H
00012 
00013 #include <rtm/idl/BasicDataTypeSkel.h>
00014 #include <rtm/Manager.h>
00015 #include <rtm/DataFlowComponentBase.h>
00016 #include <rtm/CorbaPort.h>
00017 #include <rtm/CorbaNaming.h>
00018 #include <rtm/DataInPort.h>
00019 #include <rtm/DataOutPort.h>
00020 
00021 #include <hrpUtil/EigenTypes.h>
00022 #include <hrpModel/ModelLoaderUtil.h>
00023 #include <hrpModel/Body.h>
00024 #include <hrpModel/Link.h>
00025 
00026 // Service implementation headers
00027 // <rtc-template block="service_impl_h">
00028 
00029 // </rtc-template>
00030 
00031 // Service Consumer stub headers
00032 // <rtc-template block="consumer_stub_h">
00033 
00034 // </rtc-template>
00035 
00036 using namespace RTC;
00037 
00038 class ModifiedServo  : public RTC::DataFlowComponentBase
00039 {
00040  public:
00041   ModifiedServo(RTC::Manager* manager);
00042   ~ModifiedServo();
00043 
00044   // The initialize action (on CREATED->ALIVE transition)
00045   // formaer rtc_init_entry() 
00046   virtual RTC::ReturnCode_t onInitialize();
00047 
00048   // The finalize action (on ALIVE->END transition)
00049   // formaer rtc_exiting_entry()
00050   // virtual RTC::ReturnCode_t onFinalize();
00051 
00052   // The startup action when ExecutionContext startup
00053   // former rtc_starting_entry()
00054   // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
00055 
00056   // The shutdown action when ExecutionContext stop
00057   // former rtc_stopping_entry()
00058   // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
00059 
00060   // The activated action (Active state entry action)
00061   // former rtc_active_entry()
00062   virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00063 
00064   // The deactivated action (Active state exit action)
00065   // former rtc_active_exit()
00066   virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00067 
00068   // The execution action that is invoked periodically
00069   // former rtc_active_do()
00070   virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00071 
00072   // The aborting action when main logic error occurred.
00073   // former rtc_aborting_entry()
00074   // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
00075 
00076   // The error action in ERROR state
00077   // former rtc_error_do()
00078   // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
00079 
00080   // The reset action that is invoked resetting
00081   // This is same but different the former rtc_init_entry()
00082   // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
00083   
00084   // The state update action that is invoked after onExecute() action
00085   // no corresponding operation exists in OpenRTm-aist-0.2.0
00086   // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
00087 
00088   // The action that is invoked when execution context's rate is changed
00089   // no corresponding operation exists in OpenRTm-aist-0.2.0
00090   // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
00091 
00092 
00093  protected:
00094   // Configuration variable declaration
00095   // <rtc-template block="config_declare">
00096   
00097   // </rtc-template>
00098 
00099   // DataInPort declaration
00100   // <rtc-template block="inport_declare">
00101   TimedDoubleSeq m_tauRef;
00102   InPort<TimedDoubleSeq> m_tauRefIn;
00103   TimedDoubleSeq m_qRef;
00104   InPort<TimedDoubleSeq> m_qRefIn;
00105   TimedDoubleSeq m_q;
00106   InPort<TimedDoubleSeq> m_qIn;
00107   TimedBooleanSeq m_torqueMode;
00108   InPort<TimedBooleanSeq> m_torqueModeIn;
00109 
00110   // </rtc-template>
00111 
00112   // DataOutPort declaration
00113   // <rtc-template block="outport_declare">
00114   TimedDoubleSeq m_tau;
00115   OutPort<TimedDoubleSeq> m_tauOut;
00116 
00117   // </rtc-template>
00118 
00119   // CORBA Port declaration
00120   // <rtc-template block="corbaport_declare">
00121 
00122   // </rtc-template>
00123 
00124   // Service declaration
00125   // <rtc-template block="service_declare">
00126 
00127   // </rtc-template>
00128 
00129   // Consumer declaration
00130   // <rtc-template block="consumer_declare">
00131 
00132   // </rtc-template>
00133 
00134  private:
00135 
00136   void readGainFile();
00137 
00138   hrp::BodyPtr m_robot;
00139   
00140   double dt;      // sampling time of the controller
00141   double ref_dt;  // sampling time of reference angles
00142   double step;    // current interpolation step
00143   double nstep;   // number of steps to interpolate references
00144 
00145   size_t dof;
00146 
00147   std::string gain_fname;
00148   std::ifstream gain;
00149 
00150   hrp::dvector Pgain, Dgain;
00151   hrp::dvector q_old, qRef_old;
00152 };
00153 
00154 
00155 extern "C"
00156 {
00157   DLL_EXPORT void ModifiedServoInit(RTC::Manager* manager);
00158 };
00159 
00160 #endif // MODIFIEDSERVO_H
00161 


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:18