Go to the documentation of this file.00001
00010 #ifndef REFERENCEFORCEUPDATOR_COMPONENT_H
00011 #define REFERENCEFORCEUPDATOR_COMPONENT_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 "../ImpedanceController/JointPathEx.h"
00024 #include "../ImpedanceController/RatsMatrix.h"
00025 #include "../SequencePlayer/interpolator.h"
00026
00027
00028
00029
00030 #include "ReferenceForceUpdaterService_impl.h"
00031
00032
00033
00034
00035
00036
00037
00038
00039 using namespace RTC;
00040
00044 class ReferenceForceUpdater
00045 : public RTC::DataFlowComponentBase
00046 {
00047 public:
00052 ReferenceForceUpdater(RTC::Manager* manager);
00056 virtual ~ReferenceForceUpdater();
00057
00058
00059
00060 virtual RTC::ReturnCode_t onInitialize();
00061
00062
00063
00064 virtual RTC::ReturnCode_t onFinalize();
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076 virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id);
00077
00078
00079
00080 virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id);
00081
00082
00083
00084 virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id);
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106 bool setReferenceForceUpdaterParam(const std::string& i_name_, const OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam& i_param);
00107 bool getReferenceForceUpdaterParam(const std::string& i_name_, OpenHRP::ReferenceForceUpdaterService::ReferenceForceUpdaterParam_out i_param);
00108 bool startReferenceForceUpdater(const std::string& i_name_);
00109 bool stopReferenceForceUpdater(const std::string& i_name_);
00110 void calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot);
00111 void updateRefFootOriginExtMoment (const std::string& arm);
00112 void updateRefForces (const std::string& arm);
00113 bool isFootOriginExtMoment (const std::string& str) const { return str == "footoriginextmoment"; };
00114 inline bool eps_eq(const double a, const double b, const double eps = 1e-3) { return std::fabs((a)-(b)) <= eps; };
00115
00116 protected:
00117
00118
00119
00120
00121
00122
00123
00124 TimedDoubleSeq m_qRef;
00125 InPort<TimedDoubleSeq> m_qRefIn;
00126 TimedPoint3D m_basePos;
00127 InPort<TimedPoint3D> m_basePosIn;
00128 TimedOrientation3D m_baseRpy;
00129 InPort<TimedOrientation3D> m_baseRpyIn;
00130 std::vector<TimedDoubleSeq> m_force;
00131 std::vector<InPort<TimedDoubleSeq> *> m_forceIn;
00132 std::vector<TimedDoubleSeq> m_ref_force_in;
00133 std::vector<InPort<TimedDoubleSeq> *> m_ref_forceIn;
00134 TimedOrientation3D m_rpy;
00135 InPort<TimedOrientation3D> m_rpyIn;
00136 TimedPoint3D m_diffFootOriginExtMoment;
00137 InPort<TimedPoint3D> m_diffFootOriginExtMomentIn;
00138
00139
00140
00141
00142
00143 std::vector<TimedDoubleSeq> m_ref_force_out;
00144 std::vector<OutPort<TimedDoubleSeq> *> m_ref_forceOut;
00145 TimedPoint3D m_refFootOriginExtMoment;
00146 OutPort<TimedPoint3D> m_refFootOriginExtMomentOut;
00147 TimedBoolean m_refFootOriginExtMomentIsHoldValue;
00148 OutPort<TimedBoolean> m_refFootOriginExtMomentIsHoldValueOut;
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159 RTC::CorbaPort m_ReferenceForceUpdaterServicePort;
00160
00161
00162
00163
00164
00165 ReferenceForceUpdaterService_impl m_ReferenceForceUpdaterService;
00166
00167
00168
00169 private:
00170 struct ee_trans {
00171 std::string target_name, sensor_name;
00172 hrp::Vector3 localPos;
00173 hrp::Matrix33 localR;
00174 };
00175 struct ReferenceForceUpdaterParam {
00176
00177 double update_freq;
00178
00179 double update_time_ratio;
00180
00181 double p_gain;
00182
00183 double d_gain;
00184
00185 double i_gain;
00186
00187 hrp::Vector3 motion_dir;
00188 std::string frame;
00189 int update_count;
00190 bool is_active, is_stopping, is_hold_value;
00191 ReferenceForceUpdaterParam () {
00192
00193 motion_dir = hrp::Vector3::UnitZ();
00194 frame="local";
00195 update_freq = 50;
00196 update_time_ratio = 0.5;
00197 p_gain = 0.02;
00198 d_gain = 0;
00199 i_gain = 0;
00200
00201 is_active = false;
00202 is_stopping = false;
00203 is_hold_value = false;
00204 };
00205 };
00206 std::map<std::string, hrp::VirtualForceSensorParam> m_vfs;
00207 hrp::BodyPtr m_robot;
00208 double m_dt;
00209 unsigned int m_debugLevel;
00210 coil::Mutex m_mutex;
00211 std::map<std::string, ee_trans> ee_map;
00212 std::map<std::string, size_t> ee_index_map;
00213 std::map<std::string, ReferenceForceUpdaterParam> m_RFUParam;
00214 std::vector<hrp::Vector3> ref_force;
00215 std::map<std::string, interpolator*> ref_force_interpolator;
00216 std::map<std::string, interpolator*> transition_interpolator;
00217 std::vector<double> transition_interpolator_ratio;
00218 hrp::Matrix33 foot_origin_rot;
00219 bool use_sh_base_pos_rpy;
00220 int loop;
00221 };
00222
00223
00224 extern "C"
00225 {
00226 void ReferenceForceUpdaterInit(RTC::Manager* manager);
00227 };
00228
00229 #endif // REFERENCEFORCEUPDATOR_COMPONENT_H