00001 // -*- C++ -*- 00010 #ifndef OBJECTCONTACTTURNAROUNDDETECTOR_H 00011 #define OBJECTCONTACTTURNAROUNDDETECTOR_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 <hrpUtil/Eigen3d.h> 00023 #include <hrpModel/Body.h> 00024 #include "ObjectContactTurnaroundDetectorBase.h" 00025 // Service implementation headers 00026 // <rtc-template block="service_impl_h"> 00027 #include "ObjectContactTurnaroundDetectorService_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 ObjectContactTurnaroundDetector 00039 : public RTC::DataFlowComponentBase 00040 { 00041 public: 00042 ObjectContactTurnaroundDetector(RTC::Manager* manager); 00043 virtual ~ObjectContactTurnaroundDetector(); 00044 00045 // The initialize action (on CREATED->ALIVE transition) 00046 // formaer rtc_init_entry() 00047 virtual RTC::ReturnCode_t onInitialize(); 00048 00049 // The finalize action (on ALIVE->END transition) 00050 // formaer rtc_exiting_entry() 00051 virtual RTC::ReturnCode_t onFinalize(); 00052 00053 // The startup action when ExecutionContext startup 00054 // former rtc_starting_entry() 00055 // virtual RTC::ReturnCode_t onStartup(RTC::UniqueId ec_id); 00056 00057 // The shutdown action when ExecutionContext stop 00058 // former rtc_stopping_entry() 00059 // virtual RTC::ReturnCode_t onShutdown(RTC::UniqueId ec_id); 00060 00061 // The activated action (Active state entry action) 00062 // former rtc_active_entry() 00063 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id); 00064 00065 // The deactivated action (Active state exit action) 00066 // former rtc_active_exit() 00067 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id); 00068 00069 // The execution action that is invoked periodically 00070 // former rtc_active_do() 00071 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id); 00072 00073 // The aborting action when main logic error occurred. 00074 // former rtc_aborting_entry() 00075 // virtual RTC::ReturnCode_t onAborting(RTC::UniqueId ec_id); 00076 00077 // The error action in ERROR state 00078 // former rtc_error_do() 00079 // virtual RTC::ReturnCode_t onError(RTC::UniqueId ec_id); 00080 00081 // The reset action that is invoked resetting 00082 // This is same but different the former rtc_init_entry() 00083 // virtual RTC::ReturnCode_t onReset(RTC::UniqueId ec_id); 00084 00085 // The state update action that is invoked after onExecute() action 00086 // no corresponding operation exists in OpenRTm-aist-0.2.0 00087 // virtual RTC::ReturnCode_t onStateUpdate(RTC::UniqueId ec_id); 00088 00089 // The action that is invoked when execution context's rate is changed 00090 // no corresponding operation exists in OpenRTm-aist-0.2.0 00091 // virtual RTC::ReturnCode_t onRateChanged(RTC::UniqueId ec_id); 00092 00093 void startObjectContactTurnaroundDetection(const double i_ref_diff_wrench, const double i_max_time, const OpenHRP::ObjectContactTurnaroundDetectorService::StrSequence& i_ee_names); 00094 OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode checkObjectContactTurnaroundDetection(); 00095 bool setObjectContactTurnaroundDetectorParam(const OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam &i_param_); 00096 bool getObjectContactTurnaroundDetectorParam(OpenHRP::ObjectContactTurnaroundDetectorService::objectContactTurnaroundDetectorParam& i_param_); 00097 bool getObjectForcesMoments(OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out o_forces, OpenHRP::ObjectContactTurnaroundDetectorService::Dbl3Sequence_out o_moments, OpenHRP::ObjectContactTurnaroundDetectorService::DblSequence3_out o_3dofwrench, double& o_fric_coeff_wrench); 00098 00099 protected: 00100 // Configuration variable declaration 00101 // <rtc-template block="config_declare"> 00102 00103 // </rtc-template> 00104 00105 // DataInPort declaration 00106 // <rtc-template block="inport_declare"> 00107 TimedDoubleSeq m_qCurrent; 00108 InPort<TimedDoubleSeq> m_qCurrentIn; 00109 std::vector<TimedDoubleSeq> m_force; 00110 std::vector<InPort<TimedDoubleSeq> *> m_forceIn; 00111 TimedOrientation3D m_rpy; 00112 InPort<TimedOrientation3D> m_rpyIn; 00113 TimedBooleanSeq m_contactStates; 00114 InPort<TimedBooleanSeq> m_contactStatesIn; 00115 00116 // </rtc-template> 00117 00118 // DataOutPort declaration 00119 // <rtc-template block="outport_declare"> 00120 TimedDoubleSeq m_otdData; 00121 OutPort<TimedDoubleSeq> m_otdDataOut; 00122 00123 // </rtc-template> 00124 00125 // CORBA Port declaration 00126 // <rtc-template block="corbaport_declare"> 00127 RTC::CorbaPort m_ObjectContactTurnaroundDetectorServicePort; 00128 00129 // </rtc-template> 00130 00131 // Service declaration 00132 // <rtc-template block="service_declare"> 00133 ObjectContactTurnaroundDetectorService_impl m_service0; 00134 00135 // </rtc-template> 00136 00137 // Consumer declaration 00138 // <rtc-template block="consumer_declare"> 00139 00140 // </rtc-template> 00141 00142 private: 00143 00144 struct ee_trans { 00145 std::string target_name, sensor_name; 00146 hrp::Vector3 localPos; 00147 hrp::Matrix33 localR; 00148 size_t index; 00149 }; 00150 00151 void updateRootLinkPosRot (TimedOrientation3D tmprpy); 00152 void calcFootMidCoords (hrp::Vector3& new_foot_mid_pos, hrp::Matrix33& new_foot_mid_rot); 00153 void calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot); 00154 void calcObjectContactTurnaroundDetectorState(); 00155 00156 std::map<std::string, ee_trans> ee_map; 00157 boost::shared_ptr<ObjectContactTurnaroundDetectorBase > otd; 00158 std::vector<std::string> otd_sensor_names; 00159 hrp::Vector3 otd_axis; 00160 double m_dt; 00161 hrp::BodyPtr m_robot; 00162 coil::Mutex m_mutex; 00163 unsigned int m_debugLevel; 00164 int dummy; 00165 int loop; 00166 }; 00167 00168 00169 extern "C" 00170 { 00171 void ObjectContactTurnaroundDetectorInit(RTC::Manager* manager); 00172 }; 00173 00174 #endif // OBJECTCONTACTTURNAROUNDDETECTOR_H