00001 // -*- C++ -*- 00010 #ifndef ROBOT_HARDWARE_H 00011 #define ROBOT_HARDWARE_H 00012 00013 #include <rtm/idl/BasicDataType.hh> 00014 #include <rtm/idl/ExtendedDataTypes.hh> 00015 #include "hrpsys/idl/HRPDataTypes.hh" 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 #include <hrpModel/Body.h> 00025 00026 // Service implementation headers 00027 // <rtc-template block="service_impl_h"> 00028 #include "RobotHardwareService_impl.h" 00029 00030 // </rtc-template> 00031 00032 // Service Consumer stub headers 00033 // <rtc-template block="consumer_stub_h"> 00034 00035 // </rtc-template> 00036 00037 using namespace RTC; 00038 00039 class robot; 00040 00044 class RobotHardware 00045 : public RTC::DataFlowComponentBase 00046 { 00047 public: 00052 RobotHardware(RTC::Manager* manager); 00056 virtual ~RobotHardware(); 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 virtual inline void getTimeNow(Time &tm) { 00107 coil::TimeValue coiltm(coil::gettimeofday()); 00108 tm.sec = coiltm.sec(); 00109 tm.nsec = coiltm.usec() * 1000; 00110 }; 00111 00112 protected: 00113 // Configuration variable declaration 00114 // <rtc-template block="config_declare"> 00115 int m_isDemoMode; 00116 00117 // </rtc-template> 00118 00119 // DataInPort declaration 00120 // <rtc-template block="inport_declare"> 00121 00125 TimedDoubleSeq m_qRef; 00126 InPort<TimedDoubleSeq> m_qRefIn; 00130 TimedDoubleSeq m_dqRef; 00131 InPort<TimedDoubleSeq> m_dqRefIn; 00135 TimedDoubleSeq m_tauRef; 00136 InPort<TimedDoubleSeq> m_tauRefIn; 00137 00138 // </rtc-template> 00139 00143 TimedDoubleSeq m_q; 00147 TimedDoubleSeq m_dq; 00151 TimedDoubleSeq m_tau; 00155 TimedDoubleSeq m_ctau; 00159 std::vector<TimedAcceleration3D> m_acc; 00163 std::vector<TimedAngularVelocity3D> m_rate; 00168 std::vector<TimedDoubleSeq> m_force; 00169 OpenHRP::TimedLongSeqSeq m_servoState; 00170 TimedLong m_emergencySignal; 00171 OpenHRP::RobotHardwareService::TimedRobotState2 m_rstate2; 00172 00173 // DataOutPort declaration 00174 // <rtc-template block="outport_declare"> 00175 OutPort<TimedDoubleSeq> m_qOut; 00176 OutPort<TimedDoubleSeq> m_dqOut; 00177 OutPort<TimedDoubleSeq> m_tauOut; 00178 OutPort<TimedDoubleSeq> m_ctauOut; 00179 std::vector<OutPort<TimedAcceleration3D> *> m_accOut; 00180 std::vector<OutPort<TimedAngularVelocity3D> *> m_rateOut; 00181 std::vector<OutPort<TimedDoubleSeq> *> m_forceOut; 00182 OutPort<OpenHRP::TimedLongSeqSeq> m_servoStateOut; 00183 OutPort<TimedLong> m_emergencySignalOut; 00184 OutPort<OpenHRP::RobotHardwareService::TimedRobotState2> m_rstate2Out; 00185 00186 // </rtc-template> 00187 00188 // CORBA Port declaration 00189 // <rtc-template block="corbaport_declare"> 00190 RTC::CorbaPort m_RobotHardwareServicePort; 00191 00192 // </rtc-template> 00193 00194 // Service declaration 00195 // <rtc-template block="service_declare"> 00196 RobotHardwareService_impl m_service0; 00197 00198 // </rtc-template> 00199 00200 // Consumer declaration 00201 // <rtc-template block="consumer_declare"> 00202 00203 // </rtc-template> 00204 00205 robot *robot_ptr(void) { return m_robot.get(); }; 00206 private: 00207 void getStatus2(OpenHRP::RobotHardwareService::RobotState2 &rstate2); 00208 00209 int dummy; 00210 boost::shared_ptr<robot> m_robot; 00211 }; 00212 00213 00214 extern "C" 00215 { 00216 void RobotHardwareInit(RTC::Manager* manager); 00217 }; 00218 00219 #endif // ROBOT_HARDWARE_H