Go to the documentation of this file.00001
00010 #ifndef REMOVEFORCESENSORLINKOFFSET_H
00011 #define REMOVEFORCESENSORLINKOFFSET_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 <hrpModel/Body.h>
00023 #include <hrpModel/Link.h>
00024 #include <hrpModel/JointPath.h>
00025 #include <hrpUtil/EigenTypes.h>
00026
00027 #include "RemoveForceSensorLinkOffsetService_impl.h"
00028 #include "../ImpedanceController/RatsMatrix.h"
00029 #include <semaphore.h>
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 using namespace RTC;
00042
00046 class RemoveForceSensorLinkOffset
00047 : public RTC::DataFlowComponentBase
00048 {
00049 public:
00054 RemoveForceSensorLinkOffset(RTC::Manager* manager);
00058 virtual ~RemoveForceSensorLinkOffset();
00059
00060
00061
00062 virtual RTC::ReturnCode_t onInitialize();
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00079
00080
00081
00082 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00083
00084
00085
00086 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107 bool setForceMomentOffsetParam(const std::string& i_name_, const OpenHRP::RemoveForceSensorLinkOffsetService::forcemomentOffsetParam &i_param_);
00108 bool getForceMomentOffsetParam(const std::string& i_name_, OpenHRP::RemoveForceSensorLinkOffsetService::forcemomentOffsetParam& i_param_);
00109 bool loadForceMomentOffsetParams(const std::string& filename);
00110 bool dumpForceMomentOffsetParams(const std::string& filename);
00111 bool removeForceSensorOffset (const ::OpenHRP::RemoveForceSensorLinkOffsetService::StrSequence& names, const double tm);
00112
00113 protected:
00114
00115
00116
00117
00118
00119 TimedDoubleSeq m_qCurrent;
00120 TimedOrientation3D m_rpy;
00121
00122
00123
00124 InPort<TimedDoubleSeq> m_qCurrentIn;
00125 InPort<TimedOrientation3D> m_rpyIn;
00126
00127
00128
00129
00130
00131
00132 std::vector<TimedDoubleSeq> m_force;
00133 std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
00134 std::vector<OutPort<TimedDoubleSeq> *> m_forceOut;
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150 RTC::CorbaPort m_RemoveForceSensorLinkOffsetServicePort;
00151
00152
00153
00154
00155
00156 RemoveForceSensorLinkOffsetService_impl m_service0;
00157
00158
00159
00160 private:
00161 struct ForceMomentOffsetParam {
00162 hrp::Vector3 force_offset, moment_offset, link_offset_centroid;
00163 hrp::Vector3 off_force, off_moment;
00164 double link_offset_mass;
00165
00166 hrp::Vector3 force_offset_sum, moment_offset_sum;
00167 int sensor_offset_calib_counter;
00168 sem_t wait_sem;
00169
00170 ForceMomentOffsetParam ()
00171 : force_offset(hrp::Vector3::Zero()), moment_offset(hrp::Vector3::Zero()),
00172 off_force(hrp::Vector3::Zero()), off_moment(hrp::Vector3::Zero()),
00173 link_offset_centroid(hrp::Vector3::Zero()), link_offset_mass(0),
00174 force_offset_sum(hrp::Vector3::Zero()), moment_offset_sum(hrp::Vector3::Zero()),
00175 sensor_offset_calib_counter(0), wait_sem()
00176 {
00177 sem_init(&wait_sem, 0, 0);
00178 };
00179 };
00180 void updateRootLinkPosRot (const hrp::Vector3& rpy);
00181 void printForceMomentOffsetParam(const std::string& i_name_);
00182
00183 std::map<std::string, ForceMomentOffsetParam> m_forcemoment_offset_param;
00184 #if __cplusplus >= 201103L
00185 constexpr
00186 #endif
00187 static const double grav = 9.80665;
00188 double m_dt;
00189 hrp::BodyPtr m_robot;
00190 unsigned int m_debugLevel;
00191 int max_sensor_offset_calib_counter;
00192 coil::Mutex m_mutex;
00193 };
00194
00195
00196 extern "C"
00197 {
00198 void RemoveForceSensorLinkOffsetInit(RTC::Manager* manager);
00199 };
00200
00201 #endif // REMOVEFORCESENSORLINKOFFSET_H