StateHolder.h
Go to the documentation of this file.
00001 // -*- C++ -*-
00010 #ifndef NULL_COMPONENT_H
00011 #define NULL_COMPONENT_H
00012 
00013 #include <rtm/idl/BasicDataType.hh>
00014 #include <rtm/idl/ExtendedDataTypes.hh>
00015 #include <semaphore.h>
00016 #include <rtm/Manager.h>
00017 #include <rtm/DataFlowComponentBase.h>
00018 #include <rtm/CorbaPort.h>
00019 #include <rtm/DataInPort.h>
00020 #include <rtm/DataOutPort.h>
00021 #include <rtm/idl/BasicDataTypeSkel.h>
00022 #include <rtm/idl/ExtendedDataTypesSkel.h>
00023 
00024 // Service implementation headers
00025 // <rtc-template block="service_impl_h">
00026 #include "StateHolderService_impl.h"
00027 #include "TimeKeeperService_impl.h"
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 
00040 class StateHolder
00041   : public RTC::DataFlowComponentBase
00042 {
00043  public:
00048   StateHolder(RTC::Manager* manager);
00052   virtual ~StateHolder();
00053 
00054   // The initialize action (on CREATED->ALIVE transition)
00055   // formaer rtc_init_entry()
00056   virtual RTC::ReturnCode_t onInitialize();
00057 
00058   // The finalize action (on ALIVE->END transition)
00059   // formaer rtc_exiting_entry()
00060   // virtual RTC::ReturnCode_t onFinalize();
00061 
00062   // The startup action when ExecutionContext startup
00063   // former rtc_starting_entry()
00064   // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id);
00065 
00066   // The shutdown action when ExecutionContext stop
00067   // former rtc_stopping_entry()
00068   // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id);
00069 
00070   // The activated action (Active state entry action)
00071   // former rtc_active_entry()
00072   // virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00073 
00074   // The deactivated action (Active state exit action)
00075   // former rtc_active_exit()
00076   // virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00077 
00078   // The execution action that is invoked periodically
00079   // former rtc_active_do()
00080   virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00081 
00082   // The aborting action when main logic error occurred.
00083   // former rtc_aborting_entry()
00084   // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id);
00085 
00086   // The error action in ERROR state
00087   // former rtc_error_do()
00088   // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id);
00089 
00090   // The reset action that is invoked resetting
00091   // This is same but different the former rtc_init_entry()
00092   // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id);
00093 
00094   // The state update action that is invoked after onExecute() action
00095   // no corresponding operation exists in OpenRTm-aist-0.2.0
00096   // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id);
00097 
00098   // The action that is invoked when execution context's rate is changed
00099   // no corresponding operation exists in OpenRTm-aist-0.2.0
00100   // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id);
00101 
00102   void goActual();
00103   void getCommand(StateHolderService::Command &com);  
00104 
00105   void wait(CORBA::Double tm);
00106  protected:
00107   // Configuration variable declaration
00108   // <rtc-template block="config_declare">
00109   
00110   // </rtc-template>
00111   TimedDoubleSeq m_currentQ;
00112   InPort<TimedDoubleSeq> m_currentQIn;
00113   InPort<TimedDoubleSeq> m_qIn;
00114   InPort<TimedDoubleSeq> m_tqIn;
00115   InPort<TimedPoint3D> m_basePosIn;
00116   InPort<TimedOrientation3D> m_baseRpyIn;
00117   InPort<TimedPoint3D> m_zmpIn;
00118   std::vector<InPort<TimedDoubleSeq> *> m_wrenchesIn;
00119   TimedDoubleSeq m_optionalData;
00120   InPort<TimedDoubleSeq> m_optionalDataIn;
00121 
00122   // DataInPort declaration
00123   // <rtc-template block="inport_declare">
00124   
00125   // </rtc-template>
00126 
00127   // DataOutPort declaration
00128   // <rtc-template block="outport_declare">
00129   TimedDoubleSeq m_q;
00130   TimedDoubleSeq m_tq;
00131   TimedPoint3D m_basePos;
00132   TimedOrientation3D m_baseRpy;
00133   TimedDoubleSeq m_baseTform;
00134   TimedPose3D m_basePose;
00135   TimedPoint3D m_zmp;
00136   std::vector<TimedDoubleSeq> m_wrenches;
00137   OutPort<TimedDoubleSeq> m_qOut;
00138   OutPort<TimedDoubleSeq> m_tqOut;
00139   OutPort<TimedPoint3D> m_basePosOut;
00140   OutPort<TimedOrientation3D> m_baseRpyOut;
00141   OutPort<TimedDoubleSeq> m_baseTformOut;
00142   OutPort<TimedPose3D> m_basePoseOut;
00143   OutPort<TimedPoint3D> m_zmpOut;
00144   std::vector<OutPort<TimedDoubleSeq> *> m_wrenchesOut;
00145   OutPort<TimedDoubleSeq> m_optionalDataOut;
00146 
00147   // </rtc-template>
00148 
00149   // CORBA Port declaration
00150   // <rtc-template block="corbaport_declare">
00151   RTC::CorbaPort m_StateHolderServicePort;
00152   RTC::CorbaPort m_TimeKeeperServicePort;
00153 
00154   // </rtc-template>
00155 
00156   // Service declaration
00157   // <rtc-template block="service_declare">
00158   StateHolderService_impl m_service0;
00159   TimeKeeperService_impl m_service1;  
00160 
00161   // </rtc-template>
00162 
00163   // Consumer declaration
00164   // <rtc-template block="consumer_declare">
00165   
00166   // </rtc-template>
00167 
00168  private:
00169   int m_timeCount;
00170   sem_t m_waitSem, m_timeSem;
00171   bool m_requestGoActual;
00172   double m_dt;
00173   int dummy;
00174 };
00175 
00176 
00177 extern "C"
00178 {
00179   void StateHolderInit(RTC::Manager* manager);
00180 };
00181 
00182 #endif // NULL_COMPONENT_H


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