00001 // -*- C++ -*- 00007 #ifndef ACCELERATIONFILTER_H 00008 #define ACCELERATIONFILTER_H 00009 00010 #include <rtm/idl/BasicDataTypeSkel.h> 00011 #include <rtm/Manager.h> 00012 #include <rtm/DataFlowComponentBase.h> 00013 #include <rtm/CorbaPort.h> 00014 #include <rtm/DataInPort.h> 00015 #include <rtm/DataOutPort.h> 00016 // 00017 #include <rtm/idl/BasicDataTypeSkel.h> 00018 #include <rtm/idl/ExtendedDataTypesSkel.h> 00019 // 00020 #include <hrpModel/Body.h> 00021 // 00022 #include <../TorqueFilter/IIRFilter.h> 00023 00024 // Service implementation headers 00025 // <rtc-template block="service_impl_h"> 00026 #include "AccelerationFilterService_impl.h" 00027 00028 // </rtc-template> 00029 00030 // Service Consumer stub headers 00031 // <rtc-template block="consumer_stub_h"> 00032 00033 // </rtc-template> 00034 00035 using namespace RTC; 00036 00037 class AccelerationFilter : public RTC::DataFlowComponentBase 00038 { 00039 public: 00040 AccelerationFilter(RTC::Manager* manager); 00041 ~AccelerationFilter(); 00042 00043 // The initialize action (on CREATED->ALIVE transition) 00044 // formaer rtc_init_entry() 00045 virtual RTC::ReturnCode_t onInitialize(); 00046 00047 // The finalize action (on ALIVE->END transition) 00048 // formaer rtc_exiting_entry() 00049 // virtual RTC::ReturnCode_t onFinalize(); 00050 00051 // The startup action when ExecutionContext startup 00052 // former rtc_starting_entry() 00053 // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id); 00054 00055 // The shutdown action when ExecutionContext stop 00056 // former rtc_stopping_entry() 00057 // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id); 00058 00059 // The activated action (Active state entry action) 00060 // former rtc_active_entry() 00061 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id); 00062 00063 // The deactivated action (Active state exit action) 00064 // former rtc_active_exit() 00065 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id); 00066 00067 // The execution action that is invoked periodically 00068 // former rtc_active_do() 00069 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id); 00070 00071 // The aborting action when main logic error occurred. 00072 // former rtc_aborting_entry() 00073 // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id); 00074 00075 // The error action in ERROR state 00076 // former rtc_error_do() 00077 // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id); 00078 00079 // The reset action that is invoked resetting 00080 // This is same but different the former rtc_init_entry() 00081 // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id); 00082 00083 // The state update action that is invoked after onExecute() action 00084 // no corresponding operation exists in OpenRTm-aist-0.2.0 00085 // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id); 00086 00087 // The action that is invoked when execution context's rate is changed 00088 // no corresponding operation exists in OpenRTm-aist-0.2.0 00089 // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id); 00090 bool resetFilter(const OpenHRP::AccelerationFilterService::ControlMode &mode, 00091 const double *vel); 00092 bool setParam(const ::OpenHRP::AccelerationFilterService::AccelerationFilterParam& i_param); 00093 bool getParam(::OpenHRP::AccelerationFilterService::AccelerationFilterParam &i_param); 00094 00095 protected: 00096 // Configuration variable declaration 00097 // <rtc-template block="config_declare"> 00098 // </rtc-template> 00099 00100 // DataInPort declaration 00101 // <rtc-template block="inport_declare"> 00102 TimedAcceleration3D m_accIn; 00103 InPort<TimedAcceleration3D> m_accInIn; 00104 TimedAngularVelocity3D m_rateIn; 00105 InPort<TimedAngularVelocity3D> m_rateInIn; 00106 TimedOrientation3D m_rpyIn; 00107 InPort<TimedOrientation3D> m_rpyInIn; 00108 TimedPoint3D m_posIn; 00109 InPort<TimedPoint3D> m_posInIn; 00110 // </rtc-template> 00111 00112 // DataOutPort declaration 00113 // <rtc-template block="outport_declare"> 00114 TimedVector3D m_velOut; 00115 OutPort<TimedVector3D> m_velOutOut; 00116 //TimedPoint3D m_posOut; 00117 //OutPort<TimedPoint3D> m_posOutOut; 00118 00119 // </rtc-template> 00120 00121 // CORBA Port declaration 00122 // <rtc-template block="corbaport_declare"> 00123 RTC::CorbaPort m_AccelerationFilterServicePort; 00124 00125 // </rtc-template> 00126 00127 // Service declaration 00128 // <rtc-template block="service_declare"> 00129 AccelerationFilterService_impl m_service0; 00130 00131 // </rtc-template> 00132 00133 // Consumer declaration 00134 // <rtc-template block="consumer_declare"> 00135 00136 // </rtc-template> 00137 00138 private: 00139 typedef boost::shared_ptr< IIRFilter> IIRFilterPtr; 00140 double m_dt; 00141 double m_gravity; 00142 bool m_use_filter_bool; 00143 hrp::Vector3 m_global_vel; 00144 std::vector<IIRFilterPtr > m_filters; 00145 hrp::Vector3 m_previous_pos; 00146 00147 coil::Mutex m_mutex; 00148 }; 00149 00150 00151 extern "C" 00152 { 00153 DLL_EXPORT void AccelerationFilterInit(RTC::Manager* manager); 00154 }; 00155 00156 #endif // ACCELERATIONFILTER_H 00157