ReferenceForceUpdater.h
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #ifndef REFERENCEFORCEUPDATOR_COMPONENT_H
00011 #define REFERENCEFORCEUPDATOR_COMPONENT_H
00012 
00013 #include <rtm/idl/BasicDataType.hh>
00014 #include <rtm/idl/ExtendedDataTypes.hh>
00015 #include <rtm/Manager.h>
00016 #include <rtm/DataFlowComponentBase.h>
00017 #include <rtm/CorbaPort.h>
00018 #include <rtm/DataInPort.h>
00019 #include <rtm/DataOutPort.h>
00020 #include <rtm/idl/BasicDataTypeSkel.h>
00021 #include <rtm/idl/ExtendedDataTypesSkel.h>
00022 #include <hrpModel/Body.h>
00023 #include "../ImpedanceController/JointPathEx.h"
00024 #include "../ImpedanceController/RatsMatrix.h"
00025 #include "../SequencePlayer/interpolator.h"
00026 // #include "ImpedanceOutputGenerator.h"
00027 // #include "ObjectTurnaroundDetector.h"
00028 // Service implementation headers
00029 // <rtc-template block="service_impl_h">
00030 #include "ReferenceForceUpdaterService_impl.h"
00031 
00032 // </rtc-template>
00033 
00034 // Service Consumer stub headers
00035 // <rtc-template block="consumer_stub_h">
00036 
00037 // </rtc-template>
00038 
00039 using namespace RTC;
00040 
00044 class ReferenceForceUpdater
00045   : public RTC::DataFlowComponentBase
00046 {
00047  public:
00052   ReferenceForceUpdater(RTC::Manager* manager);
00056   virtual ~ReferenceForceUpdater();
00057 
00058   // The initialize action (on CREATED->ALIVE transition)
00059   // formaer rtc_init_entry()
00060   virtual RTC::ReturnCode_t onInitialize();
00061 
00062   // The finalize action (on ALIVE->END transition)
00063   // formaer rtc_exiting_entry()
00064   virtual RTC::ReturnCode_t onFinalize();
00065 
00066   // The startup action when ExecutionContext startup
00067   // former rtc_starting_entry()
00068   // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
00069 
00070   // The shutdown action when ExecutionContext stop
00071   // former rtc_stopping_entry()
00072   // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
00073 
00074   // The activated action (Active state entry action)
00075   // former rtc_active_entry()
00076   virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00077 
00078   // The deactivated action (Active state exit action)
00079   // former rtc_active_exit()
00080   virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00081 
00082   // The execution action that is invoked periodically
00083   // former rtc_active_do()
00084   virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00085 
00086   // The aborting action when main logic error occurred.
00087   // former rtc_aborting_entry()
00088   // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
00089 
00090   // The error action in ERROR state
00091   // former rtc_error_do()
00092   // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
00093 
00094   // The reset action that is invoked resetting
00095   // This is same but different the former rtc_init_entry()
00096   // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
00097 
00098   // The state update action that is invoked after onExecute() action
00099   // no corresponding operation exists in OpenRTm-aist-0.2.0
00100   // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
00101 
00102   // The action that is invoked when execution context's rate is changed
00103   // no corresponding operation exists in OpenRTm-aist-0.2.0
00104   // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
00105 
00106   bool setReferenceForceUpdaterParam(const std::string& i_name_, const OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam& i_param);
00107   bool getReferenceForceUpdaterParam(const std::string& i_name_, OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam_out i_param);
00108   bool startReferenceForceUpdater(const std::string& i_name_);
00109   bool stopReferenceForceUpdater(const std::string& i_name_);
00110   void calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot);
00111   void updateRefFootOriginExtMoment (const std::string& arm);
00112   void updateRefForces (const std::string& arm);
00113   bool isFootOriginExtMoment (const std::string& str) const { return str == "footoriginextmoment"; };
00114   inline bool eps_eq(const double a, const double b, const double eps = 1e-3) { return std::fabs((a)-(b)) <= eps; };
00115 
00116  protected:
00117   // Configuration variable declaration
00118   // <rtc-template block="config_declare">
00119   
00120   // </rtc-template>
00121 
00122   // DataInPort declaration
00123   // <rtc-template block="inport_declare">
00124   TimedDoubleSeq m_qRef;
00125   InPort<TimedDoubleSeq> m_qRefIn;
00126   TimedPoint3D m_basePos;
00127   InPort<TimedPoint3D> m_basePosIn;
00128   TimedOrientation3D m_baseRpy;
00129   InPort<TimedOrientation3D> m_baseRpyIn;
00130   std::vector<TimedDoubleSeq> m_force;
00131   std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
00132   std::vector<TimedDoubleSeq> m_ref_force_in;
00133   std::vector<InPort<TimedDoubleSeq> *> m_ref_forceIn;
00134   TimedOrientation3D m_rpy;
00135   InPort<TimedOrientation3D> m_rpyIn;
00136   TimedPoint3D m_diffFootOriginExtMoment;
00137   InPort<TimedPoint3D> m_diffFootOriginExtMomentIn;
00138 
00139   // </rtc-template>
00140 
00141   // DataOutPort declaration
00142   // <rtc-template block="outport_declare">
00143   std::vector<TimedDoubleSeq> m_ref_force_out;
00144   std::vector<OutPort<TimedDoubleSeq> *> m_ref_forceOut;
00145   TimedPoint3D m_refFootOriginExtMoment;
00146   OutPort<TimedPoint3D> m_refFootOriginExtMomentOut;
00147   TimedBoolean m_refFootOriginExtMomentIsHoldValue;
00148   OutPort<TimedBoolean> m_refFootOriginExtMomentIsHoldValueOut;
00149 
00150   // </rtc-template>
00151 
00152   // CORBA Port declaration
00153   // <rtc-template block="corbaport_declare">
00154   
00155   // </rtc-template>
00156 
00157   // Service declaration
00158   // <rtc-template block="service_declare">
00159   RTC::CorbaPort m_ReferenceForceUpdaterServicePort;
00160   
00161   // </rtc-template>
00162 
00163   // Consumer declaration
00164   // <rtc-template block="consumer_declare">
00165   ReferenceForceUpdaterService_impl m_ReferenceForceUpdaterService;
00166   
00167   // </rtc-template>
00168 
00169  private:
00170   struct ee_trans {
00171     std::string target_name, sensor_name;
00172     hrp::Vector3 localPos;
00173     hrp::Matrix33 localR;
00174   };
00175   struct ReferenceForceUpdaterParam {
00176     // Update frequency [Hz]
00177     double update_freq;
00178     // Update time ratio \in [0,1]
00179     double update_time_ratio;
00180     // P gain
00181     double p_gain;
00182     // D gain
00183     double d_gain;
00184     // I gain
00185     double i_gain;
00186     // Motion direction to update reference force
00187     hrp::Vector3 motion_dir;
00188     std::string frame;
00189     int update_count;
00190     bool is_active, is_stopping, is_hold_value;
00191     ReferenceForceUpdaterParam () {
00192       //params defined in idl
00193       motion_dir = hrp::Vector3::UnitZ();
00194       frame="local";
00195       update_freq = 50; // Hz
00196       update_time_ratio = 0.5;
00197       p_gain = 0.02;
00198       d_gain = 0;
00199       i_gain = 0;
00200       //additional params (not defined in idl)
00201       is_active = false;
00202       is_stopping = false;
00203       is_hold_value = false;
00204     };
00205   };
00206   std::map<std::string, hrp::VirtualForceSensorParam> m_vfs;
00207   hrp::BodyPtr m_robot;
00208   double m_dt;
00209   unsigned int m_debugLevel;
00210   coil::Mutex m_mutex;
00211   std::map<std::string, ee_trans> ee_map;
00212   std::map<std::string, size_t> ee_index_map;
00213   std::map<std::string, ReferenceForceUpdaterParam> m_RFUParam;
00214   std::vector<hrp::Vector3> ref_force;
00215   std::map<std::string, interpolator*> ref_force_interpolator;
00216   std::map<std::string, interpolator*> transition_interpolator;
00217   std::vector<double> transition_interpolator_ratio;
00218   hrp::Matrix33 foot_origin_rot;
00219   bool use_sh_base_pos_rpy;
00220   int loop;//counter in onExecute
00221 };
00222 
00223 
00224 extern "C"
00225 {
00226   void ReferenceForceUpdaterInit(RTC::Manager* manager);
00227 };
00228 
00229 #endif // REFERENCEFORCEUPDATOR_COMPONENT_H


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:55