Go to the documentation of this file.00001
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
00026
00027 #include "ObjectContactTurnaroundDetectorService_impl.h"
00028
00029
00030
00031
00032
00033
00034
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
00046
00047 virtual RTC::ReturnCode_t onInitialize();
00048
00049
00050
00051 virtual RTC::ReturnCode_t onFinalize();
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00064
00065
00066
00067 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00068
00069
00070
00071 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
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 bool checkObjectContactTurnaroundDetectionForGeneralizedWrench(OpenHRP::ObjectContactTurnaroundDetectorService::DetectorModeSequence_out o_dms);
00099 bool startObjectContactTurnaroundDetectionForGeneralizedWrench();
00100 bool getObjectGeneralizedConstraintWrenches(OpenHRP::ObjectContactTurnaroundDetectorService::objectGeneralizedConstraintWrenchesParam& o_param);
00101
00102 protected:
00103
00104
00105
00106
00107
00108
00109
00110 TimedDoubleSeq m_qCurrent;
00111 InPort<TimedDoubleSeq> m_qCurrentIn;
00112 std::vector<TimedDoubleSeq> m_force;
00113 std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
00114 TimedOrientation3D m_rpy;
00115 InPort<TimedOrientation3D> m_rpyIn;
00116 TimedBooleanSeq m_contactStates;
00117 InPort<TimedBooleanSeq> m_contactStatesIn;
00118
00119
00120
00121
00122
00123 TimedDoubleSeq m_octdData;
00124 OutPort<TimedDoubleSeq> m_octdDataOut;
00125
00126
00127
00128
00129
00130 RTC::CorbaPort m_ObjectContactTurnaroundDetectorServicePort;
00131
00132
00133
00134
00135
00136 ObjectContactTurnaroundDetectorService_impl m_service0;
00137
00138
00139
00140
00141
00142
00143
00144
00145 private:
00146
00147 struct ee_trans {
00148 std::string target_name, sensor_name;
00149 hrp::Vector3 localPos;
00150 hrp::Matrix33 localR;
00151 size_t index;
00152 };
00153
00154 void updateRootLinkPosRot (TimedOrientation3D tmprpy);
00155 void calcFootMidCoords (hrp::Vector3& new_foot_mid_pos, hrp::Matrix33& new_foot_mid_rot);
00156 void calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot);
00157 void calcObjectContactTurnaroundDetectorState();
00158 OpenHRP::ObjectContactTurnaroundDetectorService::DetectorMode checkObjectContactTurnaroundDetectionCommon(const size_t index);
00159 std::string getEENameFromSensorName (const std::string& sensor_name)
00160 {
00161 std::string tmp_ee_name("");
00162 for (std::map<std::string, ee_trans>::const_iterator it = ee_map.begin(); it != ee_map.end(); it++) if (it->second.sensor_name == sensor_name) tmp_ee_name = it->first;
00163 return tmp_ee_name;
00164 };
00165
00166 std::map<std::string, ee_trans> ee_map;
00167 boost::shared_ptr<ObjectContactTurnaroundDetectorBase > octd;
00168 std::vector<std::string> octd_sensor_names;
00169 hrp::Vector3 octd_axis;
00170 double m_dt;
00171 hrp::BodyPtr m_robot;
00172 coil::Mutex m_mutex;
00173 unsigned int m_debugLevel;
00174 int dummy;
00175 int loop;
00176 };
00177
00178
00179 extern "C"
00180 {
00181 void ObjectContactTurnaroundDetectorInit(RTC::Manager* manager);
00182 };
00183
00184 #endif // OBJECTCONTACTTURNAROUNDDETECTOR_H