00001
00010 #include <rtm/CorbaNaming.h>
00011 #include <hrpModel/Link.h>
00012 #include <hrpModel/Sensor.h>
00013 #include <hrpModel/ModelLoaderUtil.h>
00014 #include "Stabilizer.h"
00015 #include "hrpsys/util/VectorConvert.h"
00016 #include <math.h>
00017 #include <boost/lambda/lambda.hpp>
00018
00019 typedef coil::Guard<coil::Mutex> Guard;
00020
00021 #ifndef deg2rad
00022 #define deg2rad(x) ((x) * M_PI / 180.0)
00023 #endif
00024 #ifndef rad2deg
00025 #define rad2deg(rad) (rad * 180 / M_PI)
00026 #endif
00027
00028
00029
00030 static const char* stabilizer_spec[] =
00031 {
00032 "implementation_id", "Stabilizer",
00033 "type_name", "Stabilizer",
00034 "description", "stabilizer",
00035 "version", HRPSYS_PACKAGE_VERSION,
00036 "vendor", "AIST",
00037 "category", "example",
00038 "activity_type", "DataFlowComponent",
00039 "max_instance", "10",
00040 "language", "C++",
00041 "lang_type", "compile",
00042
00043 "conf.default.debugLevel", "0",
00044 ""
00045 };
00046
00047
00048 static std::ostream& operator<<(std::ostream& os, const struct RTC::Time &tm)
00049 {
00050 int pre = os.precision();
00051 os.setf(std::ios::fixed);
00052 os << std::setprecision(6)
00053 << (tm.sec + tm.nsec/1e9)
00054 << std::setprecision(pre);
00055 os.unsetf(std::ios::fixed);
00056 return os;
00057 }
00058
00059 static double switching_inpact_absorber(double force, double lower_th, double upper_th);
00060
00061 Stabilizer::Stabilizer(RTC::Manager* manager)
00062 : RTC::DataFlowComponentBase(manager),
00063
00064 m_qCurrentIn("qCurrent", m_qCurrent),
00065 m_qRefIn("qRef", m_qRef),
00066 m_rpyIn("rpy", m_rpy),
00067 m_zmpRefIn("zmpRef", m_zmpRef),
00068 m_StabilizerServicePort("StabilizerService"),
00069 m_basePosIn("basePosIn", m_basePos),
00070 m_baseRpyIn("baseRpyIn", m_baseRpy),
00071 m_contactStatesIn("contactStates", m_contactStates),
00072 m_toeheelRatioIn("toeheelRatio", m_toeheelRatio),
00073 m_controlSwingSupportTimeIn("controlSwingSupportTime", m_controlSwingSupportTime),
00074 m_qRefSeqIn("qRefSeq", m_qRefSeq),
00075 m_walkingStatesIn("walkingStates", m_walkingStates),
00076 m_sbpCogOffsetIn("sbpCogOffset", m_sbpCogOffset),
00077 m_qRefOut("q", m_qRef),
00078 m_tauOut("tau", m_tau),
00079 m_zmpOut("zmp", m_zmp),
00080 m_refCPOut("refCapturePoint", m_refCP),
00081 m_actCPOut("actCapturePoint", m_actCP),
00082 m_diffCPOut("diffCapturePoint", m_diffCP),
00083 m_diffFootOriginExtMomentOut("diffFootOriginExtMoment", m_diffFootOriginExtMoment),
00084 m_actContactStatesOut("actContactStates", m_actContactStates),
00085 m_COPInfoOut("COPInfo", m_COPInfo),
00086 m_emergencySignalOut("emergencySignal", m_emergencySignal),
00087
00088 m_originRefZmpOut("originRefZmp", m_originRefZmp),
00089 m_originRefCogOut("originRefCog", m_originRefCog),
00090 m_originRefCogVelOut("originRefCogVel", m_originRefCogVel),
00091 m_originNewZmpOut("originNewZmp", m_originNewZmp),
00092 m_originActZmpOut("originActZmp", m_originActZmp),
00093 m_originActCogOut("originActCog", m_originActCog),
00094 m_originActCogVelOut("originActCogVel", m_originActCogVel),
00095 m_actBaseRpyOut("actBaseRpy", m_actBaseRpy),
00096 m_currentBasePosOut("currentBasePos", m_currentBasePos),
00097 m_currentBaseRpyOut("currentBaseRpy", m_currentBaseRpy),
00098 m_allRefWrenchOut("allRefWrench", m_allRefWrench),
00099 m_allEECompOut("allEEComp", m_allEEComp),
00100 m_debugDataOut("debugData", m_debugData),
00101 control_mode(MODE_IDLE),
00102 st_algorithm(OpenHRP::StabilizerService::TPCC),
00103 emergency_check_mode(OpenHRP::StabilizerService::NO_CHECK),
00104 szd(NULL),
00105
00106 m_debugLevel(0)
00107 {
00108 m_service0.stabilizer(this);
00109 }
00110
00111 Stabilizer::~Stabilizer()
00112 {
00113 }
00114
00115 RTC::ReturnCode_t Stabilizer::onInitialize()
00116 {
00117 std::cerr << "[" << m_profile.instance_name << "] onInitialize()" << std::endl;
00118
00119
00120 bindParameter("debugLevel", m_debugLevel, "0");
00121
00122
00123
00124
00125
00126
00127 addInPort("qCurrent", m_qCurrentIn);
00128 addInPort("qRef", m_qRefIn);
00129 addInPort("rpy", m_rpyIn);
00130 addInPort("zmpRef", m_zmpRefIn);
00131 addInPort("basePosIn", m_basePosIn);
00132 addInPort("baseRpyIn", m_baseRpyIn);
00133 addInPort("contactStates", m_contactStatesIn);
00134 addInPort("toeheelRatio", m_toeheelRatioIn);
00135 addInPort("controlSwingSupportTime", m_controlSwingSupportTimeIn);
00136 addInPort("qRefSeq", m_qRefSeqIn);
00137 addInPort("walkingStates", m_walkingStatesIn);
00138 addInPort("sbpCogOffset", m_sbpCogOffsetIn);
00139
00140
00141 addOutPort("q", m_qRefOut);
00142 addOutPort("tau", m_tauOut);
00143 addOutPort("zmp", m_zmpOut);
00144 addOutPort("refCapturePoint", m_refCPOut);
00145 addOutPort("actCapturePoint", m_actCPOut);
00146 addOutPort("diffCapturePoint", m_diffCPOut);
00147 addOutPort("diffStaticBalancePointOffset", m_diffFootOriginExtMomentOut);
00148 addOutPort("actContactStates", m_actContactStatesOut);
00149 addOutPort("COPInfo", m_COPInfoOut);
00150 addOutPort("emergencySignal", m_emergencySignalOut);
00151
00152 addOutPort("originRefZmp", m_originRefZmpOut);
00153 addOutPort("originRefCog", m_originRefCogOut);
00154 addOutPort("originRefCogVel", m_originRefCogVelOut);
00155 addOutPort("originNewZmp", m_originNewZmpOut);
00156 addOutPort("originActZmp", m_originActZmpOut);
00157 addOutPort("originActCog", m_originActCogOut);
00158 addOutPort("originActCogVel", m_originActCogVelOut);
00159 addOutPort("actBaseRpy", m_actBaseRpyOut);
00160 addOutPort("currentBasePos", m_currentBasePosOut);
00161 addOutPort("currentBaseRpy", m_currentBaseRpyOut);
00162 addOutPort("allRefWrench", m_allRefWrenchOut);
00163 addOutPort("allEEComp", m_allEECompOut);
00164 addOutPort("debugData", m_debugDataOut);
00165
00166
00167 m_StabilizerServicePort.registerProvider("service0", "StabilizerService", m_service0);
00168
00169
00170
00171
00172 addPort(m_StabilizerServicePort);
00173
00174
00175 RTC::Properties& prop = getProperties();
00176 coil::stringTo(dt, prop["dt"].c_str());
00177
00178
00179 RTC::Manager& rtcManager = RTC::Manager::instance();
00180 std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
00181 int comPos = nameServer.find(",");
00182 if (comPos < 0){
00183 comPos = nameServer.length();
00184 }
00185 nameServer = nameServer.substr(0, comPos);
00186 RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
00187
00188
00189 m_robot = hrp::BodyPtr(new hrp::Body());
00190 if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
00191 CosNaming::NamingContext::_duplicate(naming.getRootContext())
00192 )){
00193 std::cerr << "[" << m_profile.instance_name << "]failed to load model[" << prop["model"] << "]" << std::endl;
00194 return RTC::RTC_ERROR;
00195 }
00196
00197
00198 std::vector<std::string> force_sensor_names;
00199
00200
00201 int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
00202 for (unsigned int i=0; i<npforce; ++i) {
00203 force_sensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
00204 }
00205
00206
00207 readVirtualForceSensorParamFromProperties(m_vfs, m_robot, prop["virtual_force_sensor"], std::string(m_profile.instance_name));
00208 int nvforce = m_vfs.size();
00209 for (unsigned int i=0; i<nvforce; ++i) {
00210 for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it = m_vfs.begin(); it != m_vfs.end(); it++ ) {
00211 if (it->second.id == i) {
00212 force_sensor_names.push_back(it->first);
00213 }
00214 }
00215 }
00216
00217 int nforce = npforce + nvforce;
00218 m_wrenches.resize(nforce);
00219 m_wrenchesIn.resize(nforce);
00220 m_ref_wrenches.resize(nforce);
00221 m_ref_wrenchesIn.resize(nforce);
00222 m_limbCOPOffset.resize(nforce);
00223 m_limbCOPOffsetIn.resize(nforce);
00224 std::cerr << "[" << m_profile.instance_name << "] force sensor ports (" << npforce << ")" << std::endl;
00225 for (unsigned int i=0; i<nforce; ++i) {
00226 std::string force_sensor_name = force_sensor_names[i];
00227
00228 m_wrenchesIn[i] = new RTC::InPort<RTC::TimedDoubleSeq>(force_sensor_name.c_str(), m_wrenches[i]);
00229 m_wrenches[i].data.length(6);
00230 registerInPort(force_sensor_name.c_str(), *m_wrenchesIn[i]);
00231
00232 m_ref_wrenchesIn[i] = new RTC::InPort<RTC::TimedDoubleSeq>(std::string(force_sensor_name+"Ref").c_str(), m_ref_wrenches[i]);
00233 m_ref_wrenches[i].data.length(6);
00234 registerInPort(std::string(force_sensor_name+"Ref").c_str(), *m_ref_wrenchesIn[i]);
00235 std::cerr << "[" << m_profile.instance_name << "] name = " << force_sensor_name << std::endl;
00236 }
00237 std::cerr << "[" << m_profile.instance_name << "] limbCOPOffset ports (" << npforce << ")" << std::endl;
00238 for (unsigned int i=0; i<nforce; ++i) {
00239 std::string force_sensor_name = force_sensor_names[i];
00240 std::string nm("limbCOPOffset_"+force_sensor_name);
00241 m_limbCOPOffsetIn[i] = new RTC::InPort<RTC::TimedPoint3D>(nm.c_str(), m_limbCOPOffset[i]);
00242 registerInPort(nm.c_str(), *m_limbCOPOffsetIn[i]);
00243 std::cerr << "[" << m_profile.instance_name << "] name = " << nm << std::endl;
00244 }
00245
00246
00247
00248 coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
00249 if (end_effectors_str.size() > 0) {
00250 size_t prop_num = 10;
00251 size_t num = end_effectors_str.size()/prop_num;
00252 for (size_t i = 0; i < num; i++) {
00253 std::string ee_name, ee_target, ee_base;
00254 coil::stringTo(ee_name, end_effectors_str[i*prop_num].c_str());
00255 coil::stringTo(ee_target, end_effectors_str[i*prop_num+1].c_str());
00256 coil::stringTo(ee_base, end_effectors_str[i*prop_num+2].c_str());
00257 STIKParam ikp;
00258 for (size_t j = 0; j < 3; j++) {
00259 coil::stringTo(ikp.localp(j), end_effectors_str[i*prop_num+3+j].c_str());
00260 }
00261 double tmpv[4];
00262 for (int j = 0; j < 4; j++ ) {
00263 coil::stringTo(tmpv[j], end_effectors_str[i*prop_num+6+j].c_str());
00264 }
00265 ikp.localR = Eigen::AngleAxis<double>(tmpv[3], hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix();
00266 ikp.target_name = ee_target;
00267 ikp.ee_name = ee_name;
00268 {
00269 bool is_ee_exists = false;
00270 for (size_t j = 0; j < npforce; j++) {
00271 hrp::Sensor* sensor = m_robot->sensor(hrp::Sensor::FORCE, j);
00272 hrp::Link* alink = m_robot->link(ikp.target_name);
00273 while (alink != NULL && alink->name != ee_base && !is_ee_exists) {
00274 if ( alink->name == sensor->link->name ) {
00275 is_ee_exists = true;
00276 ikp.sensor_name = sensor->name;
00277 }
00278 alink = alink->parent;
00279 }
00280 }
00281 }
00282 ikp.avoid_gain = 0.001;
00283 ikp.reference_gain = 0.01;
00284 ikp.ik_loop_count = 3;
00285
00286 ikp.target_ee_diff_p = hrp::Vector3::Zero();
00287 ikp.target_ee_diff_r = hrp::Matrix33::Identity();
00288 ikp.d_rpy_swing = hrp::Vector3::Zero();
00289 ikp.d_pos_swing = hrp::Vector3::Zero();
00290 ikp.target_ee_diff_p_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(50.0, dt, hrp::Vector3::Zero()));
00291 ikp.target_ee_diff_r_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(50.0, dt, hrp::Vector3::Zero()));
00292 ikp.prev_d_pos_swing = hrp::Vector3::Zero();
00293 ikp.prev_d_rpy_swing = hrp::Vector3::Zero();
00294
00295 stikp.push_back(ikp);
00296 jpe_v.push_back(hrp::JointPathExPtr(new hrp::JointPathEx(m_robot, m_robot->link(ee_base), m_robot->link(ee_target), dt, false, std::string(m_profile.instance_name))));
00297
00298 if (ee_name.find("leg") != std::string::npos && jpe_v.back()->numJoints() == 7) {
00299 std::vector<double> optw;
00300 for (int j = 0; j < jpe_v.back()->numJoints(); j++ ) {
00301 if ( j == jpe_v.back()->numJoints()-1 ) optw.push_back(0.0);
00302 else optw.push_back(1.0);
00303 }
00304 jpe_v.back()->setOptionalWeightVector(optw);
00305 }
00306 target_ee_p.push_back(hrp::Vector3::Zero());
00307 target_ee_R.push_back(hrp::Matrix33::Identity());
00308 act_ee_p.push_back(hrp::Vector3::Zero());
00309 act_ee_R.push_back(hrp::Matrix33::Identity());
00310 projected_normal.push_back(hrp::Vector3::Zero());
00311 act_force.push_back(hrp::Vector3::Zero());
00312 ref_force.push_back(hrp::Vector3::Zero());
00313 ref_moment.push_back(hrp::Vector3::Zero());
00314 contact_states_index_map.insert(std::pair<std::string, size_t>(ee_name, i));
00315 is_ik_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) );
00316 is_feedback_control_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) );
00317 is_zmp_calc_enable.push_back( (ee_name.find("leg") != std::string::npos ? true : false) );
00318 std::cerr << "[" << m_profile.instance_name << "] End Effector [" << ee_name << "]" << std::endl;
00319 std::cerr << "[" << m_profile.instance_name << "] target = " << m_robot->link(ikp.target_name)->name << ", base = " << ee_base << ", sensor_name = " << ikp.sensor_name << std::endl;
00320 std::cerr << "[" << m_profile.instance_name << "] offset_pos = " << ikp.localp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
00321 prev_act_force_z.push_back(0.0);
00322 }
00323 m_contactStates.data.length(num);
00324 m_toeheelRatio.data.length(num);
00325 m_will_fall_counter.resize(num);
00326 }
00327
00328 std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
00329 readInterlockingJointsParamFromProperties(interlocking_joints, m_robot, prop["interlocking_joints"], std::string(m_profile.instance_name));
00330 if (interlocking_joints.size() > 0) {
00331 for (size_t i = 0; i < jpe_v.size(); i++) {
00332 std::cerr << "[" << m_profile.instance_name << "] Interlocking Joints for [" << stikp[i].ee_name << "]" << std::endl;
00333 jpe_v[i]->setInterlockingJointPairIndices(interlocking_joints, std::string(m_profile.instance_name));
00334 }
00335 }
00336
00337
00338
00339 act_zmp = hrp::Vector3::Zero();
00340 for (int i = 0; i < 2; i++) {
00341 k_tpcc_p[i] = 0.2;
00342 k_tpcc_x[i] = 4.0;
00343 k_brot_p[i] = 0.1;
00344 k_brot_tc[i] = 1.5;
00345 }
00346
00347 double k_ratio = 0.9;
00348 for (int i = 0; i < 2; i++) {
00349 eefm_k1[i] = -1.41429*k_ratio;
00350 eefm_k2[i] = -0.404082*k_ratio;
00351 eefm_k3[i] = -0.18*k_ratio;
00352 eefm_body_attitude_control_gain[i] = 0.5;
00353 eefm_body_attitude_control_time_const[i] = 1e5;
00354 }
00355 for (size_t i = 0; i < stikp.size(); i++) {
00356 STIKParam& ikp = stikp[i];
00357 hrp::Link* root = m_robot->link(ikp.target_name);
00358 ikp.eefm_rot_damping_gain = hrp::Vector3(20*5, 20*5, 1e5);
00359 ikp.eefm_rot_time_const = hrp::Vector3(1.5, 1.5, 1.5);
00360 ikp.eefm_rot_compensation_limit = deg2rad(10.0);
00361 ikp.eefm_swing_rot_spring_gain = hrp::Vector3(0.0, 0.0, 0.0);
00362 ikp.eefm_swing_rot_time_const = hrp::Vector3(1.5, 1.5, 1.5);
00363 ikp.eefm_pos_damping_gain = hrp::Vector3(3500*10, 3500*10, 3500);
00364 ikp.eefm_pos_time_const_support = hrp::Vector3(1.5, 1.5, 1.5);
00365 ikp.eefm_pos_compensation_limit = 0.025;
00366 ikp.eefm_swing_pos_spring_gain = hrp::Vector3(0.0, 0.0, 0.0);
00367 ikp.eefm_swing_pos_time_const = hrp::Vector3(1.5, 1.5, 1.5);
00368 ikp.eefm_ee_moment_limit = hrp::Vector3(1e4, 1e4, 1e4);
00369 if (ikp.ee_name.find("leg") == std::string::npos) {
00370 ikp.eefm_ee_forcemoment_distribution_weight = Eigen::Matrix<double, 6,1>::Zero();
00371 } else {
00372 for (size_t j = 0; j < 3; j++) {
00373 ikp.eefm_ee_forcemoment_distribution_weight[j] = 1;
00374 ikp.eefm_ee_forcemoment_distribution_weight[j+3] = 1e-2;
00375 }
00376 }
00377 ikp.max_limb_length = 0.0;
00378 while (!root->isRoot()) {
00379 ikp.max_limb_length += root->b.norm();
00380 ikp.parent_name = root->name;
00381 root = root->parent;
00382 }
00383 ikp.limb_length_margin = 0.13;
00384 ikp.support_time = 0.0;
00385 }
00386 eefm_swing_rot_damping_gain = hrp::Vector3(20*5, 20*5, 1e5);
00387 eefm_swing_pos_damping_gain = hrp::Vector3(33600, 33600, 7000);
00388 eefm_pos_time_const_swing = 0.08;
00389 eefm_pos_transition_time = 0.01;
00390 eefm_pos_margin_time = 0.02;
00391 eefm_zmp_delay_time_const[0] = eefm_zmp_delay_time_const[1] = 0.055;
00392
00393
00394
00395
00396 eefm_gravitational_acceleration = 9.80665;
00397 cop_check_margin = 20.0*1e-3;
00398 cp_check_margin.resize(4, 30*1e-3);
00399 cp_offset = hrp::Vector3(0.0, 0.0, 0.0);
00400 tilt_margin.resize(2, 30 * M_PI / 180);
00401 contact_decision_threshold = 50;
00402 eefm_use_force_difference_control = true;
00403 eefm_use_swing_damping = false;
00404 eefm_swing_damping_force_thre.resize(3, 300);
00405 eefm_swing_damping_moment_thre.resize(3, 15);
00406 initial_cp_too_large_error = true;
00407 is_walking = false;
00408 is_estop_while_walking = false;
00409 sbp_cog_offset = hrp::Vector3(0.0, 0.0, 0.0);
00410 use_limb_stretch_avoidance = false;
00411 use_zmp_truncation = false;
00412 limb_stretch_avoidance_time_const = 1.5;
00413 limb_stretch_avoidance_vlimit[0] = -100 * 1e-3 * dt;
00414 limb_stretch_avoidance_vlimit[1] = 50 * 1e-3 * dt;
00415 root_rot_compensation_limit[0] = root_rot_compensation_limit[1] = deg2rad(90.0);
00416 detection_count_to_air = static_cast<int>(0.0 / dt);
00417
00418
00419 double ke = 0, tc = 0;
00420 for (int i = 0; i < 2; i++) {
00421 m_tau_x[i].setup(ke, tc, dt);
00422 m_tau_x[i].setErrorPrefix(std::string(m_profile.instance_name));
00423 m_tau_y[i].setup(ke, tc, dt);
00424 m_tau_y[i].setErrorPrefix(std::string(m_profile.instance_name));
00425 m_f_z.setup(ke, tc, dt);
00426 m_f_z.setErrorPrefix(std::string(m_profile.instance_name));
00427 }
00428 pangx_ref = pangy_ref = pangx = pangy = 0;
00429 rdx = rdy = rx = ry = 0;
00430 pdr = hrp::Vector3::Zero();
00431
00432
00433 is_legged_robot = false;
00434 for (size_t i = 0; i < stikp.size(); i++) {
00435 if (stikp[i].ee_name.find("leg") == std::string::npos) continue;
00436 hrp::Sensor* sen= m_robot->sensor<hrp::ForceSensor>(stikp[i].sensor_name);
00437 if ( sen != NULL ) is_legged_robot = true;
00438 }
00439 is_emergency = false;
00440 reset_emergency_flag = false;
00441
00442 m_qCurrent.data.length(m_robot->numJoints());
00443 m_qRef.data.length(m_robot->numJoints());
00444 m_tau.data.length(m_robot->numJoints());
00445 transition_joint_q.resize(m_robot->numJoints());
00446 qorg.resize(m_robot->numJoints());
00447 qrefv.resize(m_robot->numJoints());
00448 transition_count = 0;
00449 loop = 0;
00450 m_is_falling_counter = 0;
00451 is_air_counter = 0;
00452 total_mass = m_robot->totalMass();
00453 ref_zmp_aux = hrp::Vector3::Zero();
00454 m_actContactStates.data.length(m_contactStates.data.length());
00455 for (size_t i = 0; i < m_contactStates.data.length(); i++) {
00456 ref_contact_states.push_back(true);
00457 prev_ref_contact_states.push_back(true);
00458 m_actContactStates.data[i] = false;
00459 act_contact_states.push_back(false);
00460 toeheel_ratio.push_back(1.0);
00461 }
00462 m_COPInfo.data.length(m_contactStates.data.length()*3);
00463 for (size_t i = 0; i < m_COPInfo.data.length(); i++) {
00464 m_COPInfo.data[i] = 0.0;
00465 }
00466 transition_time = 2.0;
00467 foot_origin_offset[0] = hrp::Vector3::Zero();
00468 foot_origin_offset[1] = hrp::Vector3::Zero();
00469
00470
00471 act_cogvel_filter = boost::shared_ptr<FirstOrderLowPassFilter<hrp::Vector3> >(new FirstOrderLowPassFilter<hrp::Vector3>(4.0, dt, hrp::Vector3::Zero()));
00472
00473
00474 m_originRefZmp.data.x = m_originRefZmp.data.y = m_originRefZmp.data.z = 0.0;
00475 m_originRefCog.data.x = m_originRefCog.data.y = m_originRefCog.data.z = 0.0;
00476 m_originRefCogVel.data.x = m_originRefCogVel.data.y = m_originRefCogVel.data.z = 0.0;
00477 m_originNewZmp.data.x = m_originNewZmp.data.y = m_originNewZmp.data.z = 0.0;
00478 m_originActZmp.data.x = m_originActZmp.data.y = m_originActZmp.data.z = 0.0;
00479 m_originActCog.data.x = m_originActCog.data.y = m_originActCog.data.z = 0.0;
00480 m_originActCogVel.data.x = m_originActCogVel.data.y = m_originActCogVel.data.z = 0.0;
00481 m_allRefWrench.data.length(stikp.size() * 6);
00482 m_allEEComp.data.length(stikp.size() * 6);
00483 m_debugData.data.length(1); m_debugData.data[0] = 0.0;
00484
00485
00486 szd = new SimpleZMPDistributor(dt);
00487 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
00488 for (size_t i = 0; i < stikp.size(); i++) {
00489 support_polygon_vec.push_back(std::vector<Eigen::Vector2d>(1,Eigen::Vector2d::Zero()));
00490 }
00491 szd->set_vertices(support_polygon_vec);
00492
00493 rel_ee_pos.reserve(stikp.size());
00494 rel_ee_rot.reserve(stikp.size());
00495 rel_ee_name.reserve(stikp.size());
00496
00497 hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
00498 if (sen == NULL) {
00499 std::cerr << "[" << m_profile.instance_name << "] WARNING! This robot model has no GyroSensor named 'gyrometer'! " << std::endl;
00500 }
00501 return RTC::RTC_OK;
00502 }
00503
00504
00505 RTC::ReturnCode_t Stabilizer::onFinalize()
00506 {
00507 if (szd == NULL) {
00508 delete szd;
00509 szd = NULL;
00510 }
00511 return RTC::RTC_OK;
00512 }
00513
00514
00515
00516
00517
00518
00519
00520
00521
00522
00523
00524
00525
00526
00527
00528 RTC::ReturnCode_t Stabilizer::onActivated(RTC::UniqueId ec_id)
00529 {
00530 std::cerr << "[" << m_profile.instance_name<< "] onActivated(" << ec_id << ")" << std::endl;
00531 return RTC::RTC_OK;
00532 }
00533
00534 RTC::ReturnCode_t Stabilizer::onDeactivated(RTC::UniqueId ec_id)
00535 {
00536 Guard guard(m_mutex);
00537 std::cerr << "[" << m_profile.instance_name<< "] onDeactivated(" << ec_id << ")" << std::endl;
00538 if ( (control_mode == MODE_ST || control_mode == MODE_AIR) ) {
00539 sync_2_idle ();
00540 control_mode = MODE_IDLE;
00541 transition_count = 1;
00542 }
00543 return RTC::RTC_OK;
00544 }
00545
00546 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 )
00547 #define DEBUGP2 (loop%10==0)
00548 RTC::ReturnCode_t Stabilizer::onExecute(RTC::UniqueId ec_id)
00549 {
00550 loop++;
00551
00552
00553 if (m_qRefIn.isNew()) {
00554 m_qRefIn.read();
00555 }
00556 if (m_qCurrentIn.isNew()) {
00557 m_qCurrentIn.read();
00558 }
00559 if (m_rpyIn.isNew()) {
00560 m_rpyIn.read();
00561 }
00562 if (m_zmpRefIn.isNew()) {
00563 m_zmpRefIn.read();
00564 }
00565 if (m_basePosIn.isNew()){
00566 m_basePosIn.read();
00567 }
00568 if (m_baseRpyIn.isNew()){
00569 m_baseRpyIn.read();
00570 }
00571 if (m_contactStatesIn.isNew()){
00572 m_contactStatesIn.read();
00573 for (size_t i = 0; i < m_contactStates.data.length(); i++) {
00574 ref_contact_states[i] = m_contactStates.data[i];
00575 }
00576 }
00577 if (m_toeheelRatioIn.isNew()){
00578 m_toeheelRatioIn.read();
00579 for (size_t i = 0; i < m_toeheelRatio.data.length(); i++) {
00580 toeheel_ratio[i] = m_toeheelRatio.data[i];
00581 }
00582 }
00583 if (m_controlSwingSupportTimeIn.isNew()){
00584 m_controlSwingSupportTimeIn.read();
00585 }
00586 for (size_t i = 0; i < m_wrenchesIn.size(); ++i) {
00587 if ( m_wrenchesIn[i]->isNew() ) {
00588 m_wrenchesIn[i]->read();
00589 }
00590 }
00591 for (size_t i = 0; i < m_ref_wrenchesIn.size(); ++i) {
00592 if ( m_ref_wrenchesIn[i]->isNew() ) {
00593 m_ref_wrenchesIn[i]->read();
00594 }
00595 }
00596 Guard guard(m_mutex);
00597 for (size_t i = 0; i < m_limbCOPOffsetIn.size(); ++i) {
00598 if ( m_limbCOPOffsetIn[i]->isNew() ) {
00599 m_limbCOPOffsetIn[i]->read();
00600
00601 stikp[i].localCOPPos = stikp[i].localp + stikp[i].localR * hrp::Vector3(m_limbCOPOffset[i].data.x, 0, m_limbCOPOffset[i].data.z);
00602 }
00603 }
00604 if (m_qRefSeqIn.isNew()) {
00605 m_qRefSeqIn.read();
00606 is_seq_interpolating = true;
00607 } else {
00608 is_seq_interpolating = false;
00609 }
00610 if (m_walkingStatesIn.isNew()){
00611 m_walkingStatesIn.read();
00612 is_walking = m_walkingStates.data;
00613 }
00614 if (m_sbpCogOffsetIn.isNew()){
00615 m_sbpCogOffsetIn.read();
00616 sbp_cog_offset(0) = m_sbpCogOffset.data.x;
00617 sbp_cog_offset(1) = m_sbpCogOffset.data.y;
00618 sbp_cog_offset(2) = m_sbpCogOffset.data.z;
00619 }
00620
00621 if (is_legged_robot) {
00622 getCurrentParameters();
00623 getTargetParameters();
00624 getActualParameters();
00625 calcStateForEmergencySignal();
00626 switch (control_mode) {
00627 case MODE_IDLE:
00628 break;
00629 case MODE_AIR:
00630 if ( transition_count == 0 && on_ground ) sync_2_st();
00631 break;
00632 case MODE_ST:
00633 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
00634 calcEEForceMomentControl();
00635 } else {
00636 calcTPCC();
00637 }
00638 if ( transition_count == 0 && !on_ground ) {
00639 if (is_air_counter < detection_count_to_air) ++is_air_counter;
00640 else control_mode = MODE_SYNC_TO_AIR;
00641 } else is_air_counter = 0;
00642 break;
00643 case MODE_SYNC_TO_IDLE:
00644 sync_2_idle();
00645 control_mode = MODE_IDLE;
00646 break;
00647 case MODE_SYNC_TO_AIR:
00648 sync_2_idle();
00649 control_mode = MODE_AIR;
00650 break;
00651 }
00652 }
00653 if ( m_robot->numJoints() == m_qRef.data.length() ) {
00654 if (is_legged_robot) {
00655 for ( int i = 0; i < m_robot->numJoints(); i++ ){
00656 m_qRef.data[i] = m_robot->joint(i)->q;
00657
00658 }
00659 m_zmp.data.x = rel_act_zmp(0);
00660 m_zmp.data.y = rel_act_zmp(1);
00661 m_zmp.data.z = rel_act_zmp(2);
00662 m_zmp.tm = m_qRef.tm;
00663 m_zmpOut.write();
00664 m_refCP.data.x = rel_ref_cp(0);
00665 m_refCP.data.y = rel_ref_cp(1);
00666 m_refCP.data.z = rel_ref_cp(2);
00667 m_refCP.tm = m_qRef.tm;
00668 m_refCPOut.write();
00669 m_actCP.data.x = rel_act_cp(0);
00670 m_actCP.data.y = rel_act_cp(1);
00671 m_actCP.data.z = rel_act_cp(2);
00672 m_actCP.tm = m_qRef.tm;
00673 m_actCPOut.write();
00674 {
00675 hrp::Vector3 tmp_diff_cp = ref_foot_origin_rot * (ref_cp - act_cp - cp_offset);
00676 m_diffCP.data.x = tmp_diff_cp(0);
00677 m_diffCP.data.y = tmp_diff_cp(1);
00678 m_diffCP.data.z = tmp_diff_cp(2);
00679 m_diffCP.tm = m_qRef.tm;
00680 m_diffCPOut.write();
00681 }
00682 m_diffFootOriginExtMoment.data.x = diff_foot_origin_ext_moment(0);
00683 m_diffFootOriginExtMoment.data.y = diff_foot_origin_ext_moment(1);
00684 m_diffFootOriginExtMoment.data.z = diff_foot_origin_ext_moment(2);
00685 m_diffFootOriginExtMoment.tm = m_qRef.tm;
00686 m_diffFootOriginExtMomentOut.write();
00687 m_actContactStates.tm = m_qRef.tm;
00688 m_actContactStatesOut.write();
00689 m_COPInfo.tm = m_qRef.tm;
00690 m_COPInfoOut.write();
00691
00692
00693 m_originRefZmp.data.x = ref_zmp(0); m_originRefZmp.data.y = ref_zmp(1); m_originRefZmp.data.z = ref_zmp(2);
00694 m_originRefCog.data.x = ref_cog(0); m_originRefCog.data.y = ref_cog(1); m_originRefCog.data.z = ref_cog(2);
00695 m_originRefCogVel.data.x = ref_cogvel(0); m_originRefCogVel.data.y = ref_cogvel(1); m_originRefCogVel.data.z = ref_cogvel(2);
00696 m_originNewZmp.data.x = new_refzmp(0); m_originNewZmp.data.y = new_refzmp(1); m_originNewZmp.data.z = new_refzmp(2);
00697 m_originActZmp.data.x = act_zmp(0); m_originActZmp.data.y = act_zmp(1); m_originActZmp.data.z = act_zmp(2);
00698 m_originActCog.data.x = act_cog(0); m_originActCog.data.y = act_cog(1); m_originActCog.data.z = act_cog(2);
00699 m_originActCogVel.data.x = act_cogvel(0); m_originActCogVel.data.y = act_cogvel(1); m_originActCogVel.data.z = act_cogvel(2);
00700 m_originRefZmp.tm = m_qRef.tm;
00701 m_originRefZmpOut.write();
00702 m_originRefCog.tm = m_qRef.tm;
00703 m_originRefCogOut.write();
00704 m_originRefCogVel.tm = m_qRef.tm;
00705 m_originRefCogVelOut.write();
00706 m_originNewZmp.tm = m_qRef.tm;
00707 m_originNewZmpOut.write();
00708 m_originActZmp.tm = m_qRef.tm;
00709 m_originActZmpOut.write();
00710 m_originActCog.tm = m_qRef.tm;
00711 m_originActCogOut.write();
00712 m_originActCogVel.tm = m_qRef.tm;
00713 m_originActCogVelOut.write();
00714 for (size_t i = 0; i < stikp.size(); i++) {
00715 for (size_t j = 0; j < 3; j++) {
00716 m_allRefWrench.data[6*i+j] = stikp[i].ref_force(j);
00717 m_allRefWrench.data[6*i+j+3] = stikp[i].ref_moment(j);
00718 m_allEEComp.data[6*i+j] = stikp[i].d_foot_pos(j);
00719 m_allEEComp.data[6*i+j+3] = stikp[i].d_foot_rpy(j);
00720 }
00721 }
00722 m_allRefWrench.tm = m_qRef.tm;
00723 m_allRefWrenchOut.write();
00724 m_allEEComp.tm = m_qRef.tm;
00725 m_allEECompOut.write();
00726 m_actBaseRpy.data.r = act_base_rpy(0);
00727 m_actBaseRpy.data.p = act_base_rpy(1);
00728 m_actBaseRpy.data.y = act_base_rpy(2);
00729 m_actBaseRpy.tm = m_qRef.tm;
00730 m_currentBaseRpy.data.r = current_base_rpy(0);
00731 m_currentBaseRpy.data.p = current_base_rpy(1);
00732 m_currentBaseRpy.data.y = current_base_rpy(2);
00733 m_currentBaseRpy.tm = m_qRef.tm;
00734 m_currentBasePos.data.x = current_base_pos(0);
00735 m_currentBasePos.data.y = current_base_pos(1);
00736 m_currentBasePos.data.z = current_base_pos(2);
00737 m_currentBasePos.tm = m_qRef.tm;
00738 m_actBaseRpyOut.write();
00739 m_currentBaseRpyOut.write();
00740 m_currentBasePosOut.write();
00741 m_debugData.tm = m_qRef.tm;
00742 m_debugDataOut.write();
00743 }
00744 m_qRefOut.write();
00745
00746 if (reset_emergency_flag) {
00747 m_emergencySignal.data = 0;
00748 m_emergencySignalOut.write();
00749 reset_emergency_flag = false;
00750 } else if (is_emergency) {
00751 m_emergencySignal.data = 1;
00752 m_emergencySignalOut.write();
00753 }
00754 }
00755
00756 return RTC::RTC_OK;
00757 }
00758
00759 void Stabilizer::getCurrentParameters ()
00760 {
00761 current_root_p = m_robot->rootLink()->p;
00762 current_root_R = m_robot->rootLink()->R;
00763 for ( int i = 0; i < m_robot->numJoints(); i++ ){
00764 qorg[i] = m_robot->joint(i)->q;
00765 }
00766 }
00767
00768 void Stabilizer::calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matrix33& foot_origin_rot)
00769 {
00770 rats::coordinates leg_c[2], tmpc;
00771 hrp::Vector3 ez = hrp::Vector3::UnitZ();
00772 hrp::Vector3 ex = hrp::Vector3::UnitX();
00773 for (size_t i = 0; i < stikp.size(); i++) {
00774 if (stikp[i].ee_name.find("leg") == std::string::npos) continue;
00775 hrp::Link* target = m_robot->sensor<hrp::ForceSensor>(stikp[i].sensor_name)->link;
00776 leg_c[i].pos = target->p + target->R * foot_origin_offset[i];
00777 hrp::Vector3 xv1(target->R * ex);
00778 xv1(2)=0.0;
00779 xv1.normalize();
00780 hrp::Vector3 yv1(ez.cross(xv1));
00781 leg_c[i].rot(0,0) = xv1(0); leg_c[i].rot(1,0) = xv1(1); leg_c[i].rot(2,0) = xv1(2);
00782 leg_c[i].rot(0,1) = yv1(0); leg_c[i].rot(1,1) = yv1(1); leg_c[i].rot(2,1) = yv1(2);
00783 leg_c[i].rot(0,2) = ez(0); leg_c[i].rot(1,2) = ez(1); leg_c[i].rot(2,2) = ez(2);
00784 }
00785 if (ref_contact_states[contact_states_index_map["rleg"]] &&
00786 ref_contact_states[contact_states_index_map["lleg"]]) {
00787 rats::mid_coords(tmpc, 0.5, leg_c[0], leg_c[1]);
00788 foot_origin_pos = tmpc.pos;
00789 foot_origin_rot = tmpc.rot;
00790 } else if (ref_contact_states[contact_states_index_map["rleg"]]) {
00791 foot_origin_pos = leg_c[contact_states_index_map["rleg"]].pos;
00792 foot_origin_rot = leg_c[contact_states_index_map["rleg"]].rot;
00793 } else {
00794 foot_origin_pos = leg_c[contact_states_index_map["lleg"]].pos;
00795 foot_origin_rot = leg_c[contact_states_index_map["lleg"]].rot;
00796 }
00797 }
00798
00799 void Stabilizer::getActualParameters ()
00800 {
00801
00802 hrp::Vector3 foot_origin_pos;
00803 hrp::Matrix33 foot_origin_rot;
00804 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
00805
00806 for ( int i = 0; i < m_robot->numJoints(); i++ ){
00807 m_robot->joint(i)->q = m_qCurrent.data[i];
00808 }
00809
00810 m_robot->rootLink()->p = hrp::Vector3::Zero();
00811 m_robot->calcForwardKinematics();
00812 hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
00813 hrp::Matrix33 senR = sen->link->R * sen->localR;
00814 hrp::Matrix33 act_Rs(hrp::rotFromRpy(m_rpy.data.r, m_rpy.data.p, m_rpy.data.y));
00815
00816 m_robot->rootLink()->R = act_Rs * (senR.transpose() * m_robot->rootLink()->R);
00817 m_robot->calcForwardKinematics();
00818 act_base_rpy = hrp::rpyFromRot(m_robot->rootLink()->R);
00819 calcFootOriginCoords (foot_origin_pos, foot_origin_rot);
00820 } else {
00821 for ( int i = 0; i < m_robot->numJoints(); i++ ) {
00822 m_robot->joint(i)->q = qorg[i];
00823 }
00824 m_robot->rootLink()->p = current_root_p;
00825 m_robot->rootLink()->R = current_root_R;
00826 m_robot->calcForwardKinematics();
00827 }
00828
00829 act_cog = m_robot->calcCM();
00830
00831 on_ground = false;
00832 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
00833 on_ground = calcZMP(act_zmp, zmp_origin_off+foot_origin_pos(2));
00834 } else {
00835 on_ground = calcZMP(act_zmp, ref_zmp(2));
00836 }
00837
00838 for (size_t i = 0; i < stikp.size(); i++) {
00839 std::string limb_name = stikp[i].ee_name;
00840 size_t idx = contact_states_index_map[limb_name];
00841 act_contact_states[idx] = isContact(idx);
00842 m_actContactStates.data[idx] = act_contact_states[idx];
00843 }
00844
00845
00846
00847 rel_act_zmp = m_robot->rootLink()->R.transpose() * (act_zmp - m_robot->rootLink()->p);
00848 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
00849
00850 act_zmp = foot_origin_rot.transpose() * (act_zmp - foot_origin_pos);
00851 act_cog = foot_origin_rot.transpose() * (act_cog - foot_origin_pos);
00852
00853 if (ref_contact_states != prev_ref_contact_states) {
00854 act_cogvel = (foot_origin_rot.transpose() * prev_act_foot_origin_rot) * act_cogvel;
00855 } else {
00856 act_cogvel = (act_cog - prev_act_cog)/dt;
00857 }
00858 act_cogvel = act_cogvel_filter->passFilter(act_cogvel);
00859 prev_act_cog = act_cog;
00860
00861 for (size_t i = 0; i < stikp.size(); i++) {
00862 hrp::Link* target = m_robot->link(stikp[i].target_name);
00863
00864 hrp::Vector3 _act_ee_p = target->p + target->R * stikp[i].localp;
00865 act_ee_p[i] = foot_origin_rot.transpose() * (_act_ee_p - foot_origin_pos);
00866 act_ee_R[i] = foot_origin_rot.transpose() * (target->R * stikp[i].localR);
00867 }
00868
00869 act_cp = act_cog + act_cogvel / std::sqrt(eefm_gravitational_acceleration / (act_cog - act_zmp)(2));
00870 rel_act_cp = hrp::Vector3(act_cp(0), act_cp(1), act_zmp(2));
00871 rel_act_cp = m_robot->rootLink()->R.transpose() * ((foot_origin_pos + foot_origin_rot * rel_act_cp) - m_robot->rootLink()->p);
00872
00873
00874
00875
00876
00877
00878 hrp::Vector3 dcog=foot_origin_rot * (ref_cog - act_cog);
00879 hrp::Vector3 dcogvel=foot_origin_rot * (ref_cogvel - act_cogvel);
00880 hrp::Vector3 dzmp=foot_origin_rot * (ref_zmp - act_zmp);
00881 new_refzmp = foot_origin_rot * new_refzmp + foot_origin_pos;
00882 for (size_t i = 0; i < 2; i++) {
00883 new_refzmp(i) += eefm_k1[i] * transition_smooth_gain * dcog(i) + eefm_k2[i] * transition_smooth_gain * dcogvel(i) + eefm_k3[i] * transition_smooth_gain * dzmp(i) + ref_zmp_aux(i);
00884 }
00885 if (DEBUGP) {
00886
00887 std::cerr << "[" << m_profile.instance_name << "] state values" << std::endl;
00888 std::cerr << "[" << m_profile.instance_name << "] "
00889 << "ref_cog = " << hrp::Vector3(ref_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
00890 << ", act_cog = " << hrp::Vector3(act_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
00891 std::cerr << "[" << m_profile.instance_name << "] "
00892 << "ref_cogvel = " << hrp::Vector3(ref_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
00893 << ", act_cogvel = " << hrp::Vector3(act_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm/s]" << std::endl;
00894 std::cerr << "[" << m_profile.instance_name << "] "
00895 << "ref_zmp = " << hrp::Vector3(ref_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
00896 << ", act_zmp = " << hrp::Vector3(act_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
00897 hrp::Vector3 tmpnew_refzmp;
00898 tmpnew_refzmp = foot_origin_rot.transpose()*(new_refzmp-foot_origin_pos);
00899 std::cerr << "[" << m_profile.instance_name << "] "
00900 << "new_zmp = " << hrp::Vector3(tmpnew_refzmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"))
00901 << ", dif_zmp = " << hrp::Vector3((tmpnew_refzmp-ref_zmp)*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
00902 }
00903
00904 std::vector<std::string> ee_name;
00905
00906 std::vector<hrp::Vector3> tmp_ref_force, tmp_ref_moment;
00907 std::vector<double> limb_gains;
00908 std::vector<hrp::dvector6> ee_forcemoment_distribution_weight;
00909 std::vector<double> tmp_toeheel_ratio;
00910 if (control_mode == MODE_ST) {
00911 std::vector<hrp::Vector3> ee_pos, cop_pos;
00912 std::vector<hrp::Matrix33> ee_rot;
00913 std::vector<bool> is_contact_list;
00914 is_contact_list.reserve(stikp.size());
00915 for (size_t i = 0; i < stikp.size(); i++) {
00916 STIKParam& ikp = stikp[i];
00917 if (!is_feedback_control_enable[i]) continue;
00918 hrp::Link* target = m_robot->link(ikp.target_name);
00919 ee_pos.push_back(target->p + target->R * ikp.localp);
00920 cop_pos.push_back(target->p + target->R * ikp.localCOPPos);
00921 ee_rot.push_back(target->R * ikp.localR);
00922 ee_name.push_back(ikp.ee_name);
00923 limb_gains.push_back(ikp.swing_support_gain);
00924 tmp_ref_force.push_back(hrp::Vector3(foot_origin_rot * ref_force[i]));
00925 tmp_ref_moment.push_back(hrp::Vector3(foot_origin_rot * ref_moment[i]));
00926 rel_ee_pos.push_back(foot_origin_rot.transpose() * (ee_pos.back() - foot_origin_pos));
00927 rel_ee_rot.push_back(foot_origin_rot.transpose() * ee_rot.back());
00928 rel_ee_name.push_back(ee_name.back());
00929 is_contact_list.push_back(act_contact_states[i]);
00930
00931 ee_forcemoment_distribution_weight.push_back(hrp::dvector6::Zero(6,1));
00932 for (size_t j = 0; j < 6; j++) {
00933 ee_forcemoment_distribution_weight[i][j] = ikp.eefm_ee_forcemoment_distribution_weight[j];
00934 }
00935 tmp_toeheel_ratio.push_back(toeheel_ratio[i]);
00936 }
00937
00938
00939 if (DEBUGP) {
00940 std::cerr << "[" << m_profile.instance_name << "] ee values" << std::endl;
00941 hrp::Vector3 tmpp;
00942 for (size_t i = 0; i < ee_name.size(); i++) {
00943 tmpp = foot_origin_rot.transpose()*(ee_pos[i]-foot_origin_pos);
00944 std::cerr << "[" << m_profile.instance_name << "] "
00945 << "ee_pos (" << ee_name[i] << ") = " << hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]"));
00946 tmpp = foot_origin_rot.transpose()*(cop_pos[i]-foot_origin_pos);
00947 std::cerr << ", cop_pos (" << ee_name[i] << ") = " << hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[mm]" << std::endl;
00948 }
00949 }
00950
00951
00952 if (use_zmp_truncation) {
00953 Eigen::Vector2d tmp_new_refzmp(new_refzmp.head(2));
00954 szd->get_vertices(support_polygon_vetices);
00955 szd->calc_convex_hull(support_polygon_vetices, ref_contact_states, ee_pos, ee_rot);
00956 if (!szd->is_inside_support_polygon(tmp_new_refzmp, hrp::Vector3::Zero(), true, std::string(m_profile.instance_name))) new_refzmp.head(2) = tmp_new_refzmp;
00957 }
00958
00959
00960 if (st_algorithm == OpenHRP::StabilizerService::EEFM) {
00961
00962 szd->distributeZMPToForceMoments(tmp_ref_force, tmp_ref_moment,
00963 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
00964 new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
00965 eefm_gravitational_acceleration * total_mass, dt,
00966 DEBUGP, std::string(m_profile.instance_name));
00967 } else if (st_algorithm == OpenHRP::StabilizerService::EEFMQP) {
00968 szd->distributeZMPToForceMomentsQP(tmp_ref_force, tmp_ref_moment,
00969 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
00970 new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
00971 eefm_gravitational_acceleration * total_mass, dt,
00972 DEBUGP, std::string(m_profile.instance_name),
00973 (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP));
00974 } else if (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP) {
00975 szd->distributeZMPToForceMomentsPseudoInverse(tmp_ref_force, tmp_ref_moment,
00976 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
00977 new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
00978 eefm_gravitational_acceleration * total_mass, dt,
00979 DEBUGP, std::string(m_profile.instance_name),
00980 (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP), is_contact_list);
00981 } else if (st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP2) {
00982 szd->distributeZMPToForceMomentsPseudoInverse2(tmp_ref_force, tmp_ref_moment,
00983 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
00984 new_refzmp, hrp::Vector3(foot_origin_rot * ref_zmp + foot_origin_pos),
00985 foot_origin_rot * ref_total_force, foot_origin_rot * ref_total_moment,
00986 ee_forcemoment_distribution_weight,
00987 eefm_gravitational_acceleration * total_mass, dt,
00988 DEBUGP, std::string(m_profile.instance_name));
00989 }
00990
00991 new_refzmp = foot_origin_rot.transpose() * (new_refzmp - foot_origin_pos);
00992 }
00993
00994
00995 if (control_mode == MODE_ST) {
00996 hrp::Vector3 f_diff(hrp::Vector3::Zero());
00997 std::vector<bool> large_swing_f_diff(3, false);
00998
00999 act_total_foot_origin_moment = hrp::Vector3::Zero();
01000 for (size_t i = 0; i < stikp.size(); i++) {
01001 STIKParam& ikp = stikp[i];
01002 std::vector<bool> large_swing_m_diff(3, false);
01003 if (!is_feedback_control_enable[i]) continue;
01004 hrp::Sensor* sensor = m_robot->sensor<hrp::ForceSensor>(ikp.sensor_name);
01005 hrp::Link* target = m_robot->link(ikp.target_name);
01006
01007 size_t idx = contact_states_index_map[ikp.ee_name];
01008 ikp.ref_moment = tmp_ref_moment[idx] + ((target->R * ikp.localCOPPos + target->p) - (target->R * ikp.localp + target->p)).cross(tmp_ref_force[idx]);
01009 ikp.ref_force = tmp_ref_force[idx];
01010
01011 hrp::Vector3 sensor_force = (sensor->link->R * sensor->localR) * hrp::Vector3(m_wrenches[i].data[0], m_wrenches[i].data[1], m_wrenches[i].data[2]);
01012 hrp::Vector3 sensor_moment = (sensor->link->R * sensor->localR) * hrp::Vector3(m_wrenches[i].data[3], m_wrenches[i].data[4], m_wrenches[i].data[5]);
01013
01014 hrp::Vector3 ee_moment = ((sensor->link->R * sensor->localPos + sensor->link->p) - (target->R * ikp.localp + target->p)).cross(sensor_force) + sensor_moment;
01015
01016 hrp::Matrix33 ee_R(target->R * ikp.localR);
01017
01018 ikp.ref_moment = ee_R.transpose() * ikp.ref_moment;
01019 ikp.ref_force = ee_R.transpose() * ikp.ref_force;
01020 sensor_force = ee_R.transpose() * sensor_force;
01021 ee_moment = ee_R.transpose() * ee_moment;
01022 if ( i == 0 ) f_diff += -1*sensor_force;
01023 else f_diff += sensor_force;
01024 for (size_t j = 0; j < 3; ++j) {
01025 if ((!ref_contact_states[i] || !act_contact_states[i]) && fabs(ikp.ref_force(j) - sensor_force(j)) > eefm_swing_damping_force_thre[j]) large_swing_f_diff[j] = true;
01026 if ((!ref_contact_states[i] || !act_contact_states[i]) && (fabs(ikp.ref_moment(j) - ee_moment(j)) > eefm_swing_damping_moment_thre[j])) large_swing_m_diff[j] = true;
01027 }
01028
01029 ikp.ref_moment = ee_R * vlimit((ee_R.transpose() * ikp.ref_moment), ikp.eefm_ee_moment_limit);
01030
01031
01032 {
01033
01034 hrp::Vector3 tmp_damping_gain;
01035 for (size_t j = 0; j < 3; ++j) {
01036 if (!eefm_use_swing_damping || !large_swing_m_diff[j]) tmp_damping_gain(j) = (1-transition_smooth_gain) * ikp.eefm_rot_damping_gain(j) * 10 + transition_smooth_gain * ikp.eefm_rot_damping_gain(j);
01037 else tmp_damping_gain(j) = (1-transition_smooth_gain) * eefm_swing_rot_damping_gain(j) * 10 + transition_smooth_gain * eefm_swing_rot_damping_gain(j);
01038 }
01039 ikp.ee_d_foot_rpy = calcDampingControl(ikp.ref_moment, ee_moment, ikp.ee_d_foot_rpy, tmp_damping_gain, ikp.eefm_rot_time_const);
01040 ikp.ee_d_foot_rpy = vlimit(ikp.ee_d_foot_rpy, -1 * ikp.eefm_rot_compensation_limit, ikp.eefm_rot_compensation_limit);
01041 }
01042 if (!eefm_use_force_difference_control) {
01043 hrp::Vector3 tmp_damping_gain = (1-transition_smooth_gain) * ikp.eefm_pos_damping_gain * 10 + transition_smooth_gain * ikp.eefm_pos_damping_gain;
01044 ikp.ee_d_foot_pos = calcDampingControl(ikp.ref_force, sensor_force, ikp.ee_d_foot_pos, tmp_damping_gain, ikp.eefm_pos_time_const_support);
01045 ikp.ee_d_foot_pos = vlimit(ikp.ee_d_foot_pos, -1 * ikp.eefm_pos_compensation_limit, ikp.eefm_pos_compensation_limit);
01046 }
01047
01048 ikp.ref_moment = foot_origin_rot.transpose() * ee_R * ikp.ref_moment;
01049 ikp.ref_force = foot_origin_rot.transpose() * ee_R * ikp.ref_force;
01050 sensor_force = foot_origin_rot.transpose() * ee_R * sensor_force;
01051 ee_moment = foot_origin_rot.transpose() * ee_R * ee_moment;
01052 ikp.d_foot_rpy = foot_origin_rot.transpose() * ee_R * ikp.ee_d_foot_rpy;
01053 ikp.d_foot_pos = foot_origin_rot.transpose() * ee_R * ikp.ee_d_foot_pos;
01054
01055 {
01056 hrp::Vector3 plane_x = target_ee_R[i].col(0);
01057 hrp::Vector3 plane_y = target_ee_R[i].col(1);
01058 hrp::Matrix33 act_ee_R_world = target->R * stikp[i].localR;
01059 hrp::Vector3 normal_vector = act_ee_R_world.col(2);
01060
01061 projected_normal.at(i) = plane_x.dot(normal_vector) * plane_x + plane_y.dot(normal_vector) * plane_y;
01062 act_force.at(i) = sensor_force;
01063 }
01064
01065 act_total_foot_origin_moment += (target->R * ikp.localp + target->p - foot_origin_pos).cross(sensor_force) + ee_moment;
01066 }
01067 act_total_foot_origin_moment = foot_origin_rot.transpose() * act_total_foot_origin_moment;
01068
01069 if (eefm_use_force_difference_control) {
01070
01071
01072
01073 hrp::Vector3 ref_f_diff = (stikp[1].ref_force-stikp[0].ref_force);
01074 if (ref_contact_states != prev_ref_contact_states) pos_ctrl = (foot_origin_rot.transpose() * prev_act_foot_origin_rot) * pos_ctrl;
01075 if (eefm_use_swing_damping) {
01076 hrp::Vector3 tmp_damping_gain;
01077 for (size_t i = 0; i < 3; ++i) {
01078 if (!large_swing_f_diff[i]) tmp_damping_gain(i) = (1-transition_smooth_gain) * stikp[0].eefm_pos_damping_gain(i) * 10 + transition_smooth_gain * stikp[0].eefm_pos_damping_gain(i);
01079 else tmp_damping_gain(i) = (1-transition_smooth_gain) * eefm_swing_pos_damping_gain(i) * 10 + transition_smooth_gain * eefm_swing_pos_damping_gain(i);
01080 }
01081 pos_ctrl = calcDampingControl (ref_f_diff, f_diff, pos_ctrl,
01082 tmp_damping_gain, stikp[0].eefm_pos_time_const_support);
01083 } else {
01084 if ( (ref_contact_states[contact_states_index_map["rleg"]] && ref_contact_states[contact_states_index_map["lleg"]])
01085 || (act_contact_states[0] && act_contact_states[1]) ) {
01086
01087 hrp::Vector3 tmp_damping_gain = (1-transition_smooth_gain) * stikp[0].eefm_pos_damping_gain * 10 + transition_smooth_gain * stikp[0].eefm_pos_damping_gain;
01088 pos_ctrl = calcDampingControl (ref_f_diff, f_diff, pos_ctrl,
01089 tmp_damping_gain, stikp[0].eefm_pos_time_const_support);
01090 } else {
01091 double remain_swing_time;
01092 if ( !ref_contact_states[contact_states_index_map["rleg"]] ) {
01093 remain_swing_time = m_controlSwingSupportTime.data[contact_states_index_map["rleg"]];
01094 } else {
01095 remain_swing_time = m_controlSwingSupportTime.data[contact_states_index_map["lleg"]];
01096 }
01097
01098 double tmp_ratio = std::max(0.0, std::min(1.0, 1.0 - (remain_swing_time-eefm_pos_margin_time)/eefm_pos_transition_time));
01099
01100 hrp::Vector3 tmp_damping_gain = (1-transition_smooth_gain) * stikp[0].eefm_pos_damping_gain * 10 + transition_smooth_gain * stikp[0].eefm_pos_damping_gain;
01101 hrp::Vector3 tmp_time_const = (1-tmp_ratio)*eefm_pos_time_const_swing*hrp::Vector3::Ones()+tmp_ratio*stikp[0].eefm_pos_time_const_support;
01102 pos_ctrl = calcDampingControl (tmp_ratio * ref_f_diff, tmp_ratio * f_diff, pos_ctrl, tmp_damping_gain, tmp_time_const);
01103 }
01104 }
01105
01106
01107 pos_ctrl = vlimit(pos_ctrl, -1 * stikp[0].eefm_pos_compensation_limit * 2, stikp[0].eefm_pos_compensation_limit * 2);
01108
01109 stikp[0].d_foot_pos = -0.5 * pos_ctrl;
01110 stikp[1].d_foot_pos = 0.5 * pos_ctrl;
01111 }
01112 if (DEBUGP) {
01113 std::cerr << "[" << m_profile.instance_name << "] Control values" << std::endl;
01114 if (eefm_use_force_difference_control) {
01115 std::cerr << "[" << m_profile.instance_name << "] "
01116 << "pos_ctrl = [" << pos_ctrl(0)*1e3 << " " << pos_ctrl(1)*1e3 << " "<< pos_ctrl(2)*1e3 << "] [mm]" << std::endl;
01117 }
01118 for (size_t i = 0; i < ee_name.size(); i++) {
01119 std::cerr << "[" << m_profile.instance_name << "] "
01120 << "d_foot_pos (" << ee_name[i] << ") = [" << stikp[i].d_foot_pos(0)*1e3 << " " << stikp[i].d_foot_pos(1)*1e3 << " " << stikp[i].d_foot_pos(2)*1e3 << "] [mm], "
01121 << "d_foot_rpy (" << ee_name[i] << ") = [" << stikp[i].d_foot_rpy(0)*180.0/M_PI << " " << stikp[i].d_foot_rpy(1)*180.0/M_PI << " " << stikp[i].d_foot_rpy(2)*180.0/M_PI << "] [deg]" << std::endl;
01122 }
01123 }
01124
01125
01126
01127
01128
01129
01130 calcDiffFootOriginExtMoment ();
01131 }
01132 }
01133
01134 for ( int i = 0; i < m_robot->numJoints(); i++ ){
01135 m_robot->joint(i)->q = qrefv[i];
01136 }
01137 m_robot->rootLink()->p = target_root_p;
01138 m_robot->rootLink()->R = target_root_R;
01139 if ( !(control_mode == MODE_IDLE || control_mode == MODE_AIR) ) {
01140 for (size_t i = 0; i < jpe_v.size(); i++) {
01141 if (is_ik_enable[i]) {
01142 for ( int j = 0; j < jpe_v[i]->numJoints(); j++ ){
01143 int idx = jpe_v[i]->joint(j)->jointId;
01144 m_robot->joint(idx)->q = qorg[idx];
01145 }
01146 }
01147 }
01148 m_robot->rootLink()->p(0) = current_root_p(0);
01149 m_robot->rootLink()->p(1) = current_root_p(1);
01150 m_robot->rootLink()->R = current_root_R;
01151 m_robot->calcForwardKinematics();
01152 }
01153 copy (ref_contact_states.begin(), ref_contact_states.end(), prev_ref_contact_states.begin());
01154 if (control_mode != MODE_ST) d_pos_z_root = 0.0;
01155 prev_act_foot_origin_rot = foot_origin_rot;
01156 }
01157
01158 void Stabilizer::getTargetParameters ()
01159 {
01160
01161
01162 if ( transition_count == 0 ) {
01163 transition_smooth_gain = 1.0;
01164 } else {
01165 double max_transition_count = calcMaxTransitionCount();
01166 transition_smooth_gain = 1/(1+exp(-9.19*(((max_transition_count - std::fabs(transition_count)) / max_transition_count) - 0.5)));
01167 }
01168 if (transition_count > 0) {
01169 for ( int i = 0; i < m_robot->numJoints(); i++ ){
01170 m_robot->joint(i)->q = ( m_qRef.data[i] - transition_joint_q[i] ) * transition_smooth_gain + transition_joint_q[i];
01171 }
01172 } else {
01173 for ( int i = 0; i < m_robot->numJoints(); i++ ){
01174 m_robot->joint(i)->q = m_qRef.data[i];
01175 }
01176 }
01177 if ( transition_count < 0 ) {
01178 transition_count++;
01179 } else if ( transition_count > 0 ) {
01180 if ( transition_count == 1 ) {
01181 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm << "] Move to MODE_IDLE" << std::endl;
01182 reset_emergency_flag = true;
01183 }
01184 transition_count--;
01185 }
01186 for ( int i = 0; i < m_robot->numJoints(); i++ ){
01187 qrefv[i] = m_robot->joint(i)->q;
01188 }
01189 m_robot->rootLink()->p = hrp::Vector3(m_basePos.data.x, m_basePos.data.y, m_basePos.data.z);
01190 target_root_p = m_robot->rootLink()->p;
01191 target_root_R = hrp::rotFromRpy(m_baseRpy.data.r, m_baseRpy.data.p, m_baseRpy.data.y);
01192 m_robot->rootLink()->R = target_root_R;
01193 m_robot->calcForwardKinematics();
01194 ref_zmp = m_robot->rootLink()->R * hrp::Vector3(m_zmpRef.data.x, m_zmpRef.data.y, m_zmpRef.data.z) + m_robot->rootLink()->p;
01195 hrp::Vector3 foot_origin_pos;
01196 hrp::Matrix33 foot_origin_rot;
01197 calcFootOriginCoords (foot_origin_pos, foot_origin_rot);
01198 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
01199
01200 hrp::Vector3 tmp_ref_zmp = ref_zmp + eefm_zmp_delay_time_const[0] * (ref_zmp - prev_ref_zmp) / dt;
01201 prev_ref_zmp = ref_zmp;
01202 ref_zmp = tmp_ref_zmp;
01203 }
01204 ref_cog = m_robot->calcCM();
01205 ref_total_force = hrp::Vector3::Zero();
01206 ref_total_moment = hrp::Vector3::Zero();
01207 ref_total_foot_origin_moment = hrp::Vector3::Zero();
01208 for (size_t i = 0; i < stikp.size(); i++) {
01209 hrp::Link* target = m_robot->link(stikp[i].target_name);
01210
01211 target_ee_p[i] = target->p + target->R * stikp[i].localp;
01212 target_ee_R[i] = target->R * stikp[i].localR;
01213 ref_force[i] = hrp::Vector3(m_ref_wrenches[i].data[0], m_ref_wrenches[i].data[1], m_ref_wrenches[i].data[2]);
01214 ref_moment[i] = hrp::Vector3(m_ref_wrenches[i].data[3], m_ref_wrenches[i].data[4], m_ref_wrenches[i].data[5]);
01215 ref_total_force += ref_force[i];
01216 #ifdef FORCE_MOMENT_DIFF_CONTROL
01217
01218 ref_total_moment += (target_ee_p[i]-ref_zmp).cross(ref_force[i]);
01219 #else
01220
01221 ref_total_moment += (target_ee_p[i]-ref_zmp).cross(hrp::Vector3(m_ref_wrenches[i].data[0], m_ref_wrenches[i].data[1], m_ref_wrenches[i].data[2]))
01222 + hrp::Vector3(m_ref_wrenches[i].data[3], m_ref_wrenches[i].data[4], m_ref_wrenches[i].data[5]);
01223 #endif
01224 if (is_feedback_control_enable[i]) {
01225 ref_total_foot_origin_moment += (target_ee_p[i]-foot_origin_pos).cross(ref_force[i]) + ref_moment[i];
01226 }
01227 }
01228
01229
01230
01231 if (transition_count == (-1 * calcMaxTransitionCount() + 1)) {
01232 prev_ref_cog = ref_cog;
01233 std::cerr << "[" << m_profile.instance_name << "] Reset prev_ref_cog for transition (MODE_IDLE=>MODE_ST)." << std::endl;
01234 }
01235
01236 if (st_algorithm != OpenHRP::StabilizerService::TPCC) {
01237
01238
01239 new_refzmp = ref_zmp;
01240 rel_cog = m_robot->rootLink()->R.transpose() * (ref_cog-m_robot->rootLink()->p);
01241
01242 zmp_origin_off = ref_zmp(2) - foot_origin_pos(2);
01243 ref_zmp = foot_origin_rot.transpose() * (ref_zmp - foot_origin_pos);
01244 ref_cog = foot_origin_rot.transpose() * (ref_cog - foot_origin_pos);
01245 new_refzmp = foot_origin_rot.transpose() * (new_refzmp - foot_origin_pos);
01246 if (ref_contact_states != prev_ref_contact_states) {
01247 ref_cogvel = (foot_origin_rot.transpose() * prev_ref_foot_origin_rot) * ref_cogvel;
01248 } else {
01249 ref_cogvel = (ref_cog - prev_ref_cog)/dt;
01250 }
01251 prev_ref_foot_origin_rot = ref_foot_origin_rot = foot_origin_rot;
01252 for (size_t i = 0; i < stikp.size(); i++) {
01253 stikp[i].target_ee_diff_p = foot_origin_rot.transpose() * (target_ee_p[i] - foot_origin_pos);
01254 stikp[i].target_ee_diff_r = foot_origin_rot.transpose() * target_ee_R[i];
01255 ref_force[i] = foot_origin_rot.transpose() * ref_force[i];
01256 ref_moment[i] = foot_origin_rot.transpose() * ref_moment[i];
01257 }
01258 ref_total_foot_origin_moment = foot_origin_rot.transpose() * ref_total_foot_origin_moment;
01259 ref_total_force = foot_origin_rot.transpose() * ref_total_force;
01260 ref_total_moment = foot_origin_rot.transpose() * ref_total_moment;
01261 target_foot_origin_rot = foot_origin_rot;
01262
01263 ref_cp = ref_cog + ref_cogvel / std::sqrt(eefm_gravitational_acceleration / (ref_cog - ref_zmp)(2));
01264 rel_ref_cp = hrp::Vector3(ref_cp(0), ref_cp(1), ref_zmp(2));
01265 rel_ref_cp = m_robot->rootLink()->R.transpose() * ((foot_origin_pos + foot_origin_rot * rel_ref_cp) - m_robot->rootLink()->p);
01266 sbp_cog_offset = foot_origin_rot.transpose() * sbp_cog_offset;
01267
01268 } else {
01269 ref_cogvel = (ref_cog - prev_ref_cog)/dt;
01270 }
01271 prev_ref_cog = ref_cog;
01272
01273 calcSwingSupportLimbGain();
01274 }
01275
01276 bool Stabilizer::calcZMP(hrp::Vector3& ret_zmp, const double zmp_z)
01277 {
01278 double tmpzmpx = 0;
01279 double tmpzmpy = 0;
01280 double tmpfz = 0, tmpfz2 = 0.0;
01281 for (size_t i = 0; i < stikp.size(); i++) {
01282 if (!is_zmp_calc_enable[i]) continue;
01283 hrp::ForceSensor* sensor = m_robot->sensor<hrp::ForceSensor>(stikp[i].sensor_name);
01284 hrp::Vector3 fsp = sensor->link->p + sensor->link->R * sensor->localPos;
01285 hrp::Matrix33 tmpR;
01286 rats::rotm3times(tmpR, sensor->link->R, sensor->localR);
01287 hrp::Vector3 nf = tmpR * hrp::Vector3(m_wrenches[i].data[0], m_wrenches[i].data[1], m_wrenches[i].data[2]);
01288 hrp::Vector3 nm = tmpR * hrp::Vector3(m_wrenches[i].data[3], m_wrenches[i].data[4], m_wrenches[i].data[5]);
01289 tmpzmpx += nf(2) * fsp(0) - (fsp(2) - zmp_z) * nf(0) - nm(1);
01290 tmpzmpy += nf(2) * fsp(1) - (fsp(2) - zmp_z) * nf(1) + nm(0);
01291 tmpfz += nf(2);
01292
01293 hrp::Link* target = m_robot->link(stikp[i].target_name);
01294 hrp::Matrix33 eeR = target->R * stikp[i].localR;
01295 hrp::Vector3 ee_fsp = eeR.transpose() * (fsp - (target->p + target->R * stikp[i].localp));
01296 nf = eeR.transpose() * nf;
01297 nm = eeR.transpose() * nm;
01298
01299 double tmpcopmy = nf(2) * ee_fsp(0) - nf(0) * ee_fsp(2) - nm(1);
01300 double tmpcopmx = nf(2) * ee_fsp(1) - nf(1) * ee_fsp(2) + nm(0);
01301 double tmpcopfz = nf(2);
01302 m_COPInfo.data[i*3] = tmpcopmx;
01303 m_COPInfo.data[i*3+1] = tmpcopmy;
01304 m_COPInfo.data[i*3+2] = tmpcopfz;
01305 prev_act_force_z[i] = 0.85 * prev_act_force_z[i] + 0.15 * nf(2);
01306 tmpfz2 += prev_act_force_z[i];
01307 }
01308 if (tmpfz2 < contact_decision_threshold) {
01309 ret_zmp = act_zmp;
01310 return false;
01311 } else {
01312 ret_zmp = hrp::Vector3(tmpzmpx / tmpfz, tmpzmpy / tmpfz, zmp_z);
01313 return true;
01314 }
01315 };
01316
01317 void Stabilizer::calcStateForEmergencySignal()
01318 {
01319
01320 bool is_cop_outside = false;
01321 if (DEBUGP) {
01322 std::cerr << "[" << m_profile.instance_name << "] Check Emergency State (seq = " << (is_seq_interpolating?"interpolating":"empty") << ")" << std::endl;
01323 }
01324 if (on_ground && transition_count == 0 && control_mode == MODE_ST) {
01325 if (DEBUGP) {
01326 std::cerr << "[" << m_profile.instance_name << "] COP check" << std::endl;
01327 }
01328 for (size_t i = 0; i < stikp.size(); i++) {
01329 if (stikp[i].ee_name.find("leg") == std::string::npos) continue;
01330
01331 if (m_COPInfo.data[i*3+2] > 20.0 ) {
01332 hrp::Vector3 tmpcop(m_COPInfo.data[i*3+1]/m_COPInfo.data[i*3+2], m_COPInfo.data[i*3]/m_COPInfo.data[i*3+2], 0);
01333 is_cop_outside = is_cop_outside ||
01334 (!szd->is_inside_foot(tmpcop, stikp[i].ee_name=="lleg", cop_check_margin) ||
01335 szd->is_front_of_foot(tmpcop, cop_check_margin) ||
01336 szd->is_rear_of_foot(tmpcop, cop_check_margin));
01337 if (DEBUGP) {
01338 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[i].ee_name << "] "
01339 << "outside(" << !szd->is_inside_foot(tmpcop, stikp[i].ee_name=="lleg", cop_check_margin) << ") "
01340 << "front(" << szd->is_front_of_foot(tmpcop, cop_check_margin) << ") "
01341 << "rear(" << szd->is_rear_of_foot(tmpcop, cop_check_margin) << ")" << std::endl;
01342 }
01343 } else {
01344 is_cop_outside = true;
01345 }
01346 }
01347 } else {
01348 is_cop_outside = false;
01349 }
01350
01351 bool is_cp_outside = false;
01352 if (on_ground && transition_count == 0 && control_mode == MODE_ST) {
01353 Eigen::Vector2d tmp_cp = act_cp.head(2);
01354 szd->get_margined_vertices(margined_support_polygon_vetices);
01355 szd->calc_convex_hull(margined_support_polygon_vetices, act_contact_states, rel_ee_pos, rel_ee_rot);
01356 if (!is_walking || is_estop_while_walking) is_cp_outside = !szd->is_inside_support_polygon(tmp_cp, - sbp_cog_offset);
01357 if (DEBUGP) {
01358 std::cerr << "[" << m_profile.instance_name << "] CP value " << "[" << act_cp(0) << "," << act_cp(1) << "] [m], "
01359 << "sbp cog offset [" << sbp_cog_offset(0) << " " << sbp_cog_offset(1) << "], outside ? "
01360 << (is_cp_outside?"Outside":"Inside")
01361 << std::endl;
01362 }
01363 if (is_cp_outside) {
01364 if (initial_cp_too_large_error || loop % static_cast <int>(0.2/dt) == 0 ) {
01365 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm
01366 << "] CP too large error " << "[" << act_cp(0) << "," << act_cp(1) << "] [m]" << std::endl;
01367 }
01368 initial_cp_too_large_error = false;
01369 } else {
01370 initial_cp_too_large_error = true;
01371 }
01372 }
01373
01374 hrp::Vector3 fall_direction = hrp::Vector3::Zero();
01375 bool is_falling = false, will_fall = false;
01376 {
01377 double total_force = 0.0;
01378 for (size_t i = 0; i < stikp.size(); i++) {
01379 if (is_zmp_calc_enable[i]) {
01380 if (is_walking) {
01381 if (projected_normal.at(i).norm() > sin(tilt_margin[0])) {
01382 will_fall = true;
01383 if (m_will_fall_counter[i] % static_cast <int>(1.0/dt) == 0 ) {
01384 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm
01385 << "] " << stikp[i].ee_name << " cannot support total weight, "
01386 << "swgsuptime : " << m_controlSwingSupportTime.data[i] << ", state : " << ref_contact_states[i]
01387 << ", otherwise robot will fall down toward " << "(" << projected_normal.at(i)(0) << "," << projected_normal.at(i)(1) << ") direction" << std::endl;
01388 }
01389 m_will_fall_counter[i]++;
01390 } else {
01391 m_will_fall_counter[i] = 0;
01392 }
01393 }
01394 fall_direction += projected_normal.at(i) * act_force.at(i).norm();
01395 total_force += act_force.at(i).norm();
01396 }
01397 }
01398 if (on_ground && transition_count == 0 && control_mode == MODE_ST) {
01399 fall_direction = fall_direction / total_force;
01400 } else {
01401 fall_direction = hrp::Vector3::Zero();
01402 }
01403 if (fall_direction.norm() > sin(tilt_margin[1])) {
01404 is_falling = true;
01405 if (m_is_falling_counter % static_cast <int>(0.2/dt) == 0) {
01406 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm
01407 << "] robot is falling down toward " << "(" << fall_direction(0) << "," << fall_direction(1) << ") direction" << std::endl;
01408 }
01409 m_is_falling_counter++;
01410 } else {
01411 m_is_falling_counter = 0;
01412 }
01413 }
01414
01415 switch (emergency_check_mode) {
01416 case OpenHRP::StabilizerService::NO_CHECK:
01417 is_emergency = false;
01418 break;
01419 case OpenHRP::StabilizerService::COP:
01420 is_emergency = is_cop_outside && is_seq_interpolating;
01421 break;
01422 case OpenHRP::StabilizerService::CP:
01423 is_emergency = is_cp_outside;
01424 break;
01425 case OpenHRP::StabilizerService::TILT:
01426 is_emergency = will_fall || is_falling;
01427 break;
01428 default:
01429 break;
01430 }
01431 if (DEBUGP) {
01432 std::cerr << "[" << m_profile.instance_name << "] EmergencyCheck ("
01433 << (emergency_check_mode == OpenHRP::StabilizerService::NO_CHECK?"NO_CHECK": (emergency_check_mode == OpenHRP::StabilizerService::COP?"COP":"CP") )
01434 << ") " << (is_emergency?"emergency":"non-emergency") << std::endl;
01435 }
01436 rel_ee_pos.clear();
01437 rel_ee_rot.clear();
01438 rel_ee_name.clear();
01439 };
01440
01441 void Stabilizer::moveBasePosRotForBodyRPYControl ()
01442 {
01443
01444
01445 hrp::Vector3 ref_root_rpy = hrp::rpyFromRot(target_root_R);
01446 bool is_root_rot_limit = false;
01447 for (size_t i = 0; i < 2; i++) {
01448 d_rpy[i] = transition_smooth_gain * (eefm_body_attitude_control_gain[i] * (ref_root_rpy(i) - act_base_rpy(i)) - 1/eefm_body_attitude_control_time_const[i] * d_rpy[i]) * dt + d_rpy[i];
01449 d_rpy[i] = vlimit(d_rpy[i], -1 * root_rot_compensation_limit[i], root_rot_compensation_limit[i]);
01450 is_root_rot_limit = is_root_rot_limit || (std::fabs(std::fabs(d_rpy[i]) - root_rot_compensation_limit[i] ) < 1e-5);
01451 }
01452 rats::rotm3times(current_root_R, target_root_R, hrp::rotFromRpy(d_rpy[0], d_rpy[1], 0));
01453 m_robot->rootLink()->R = current_root_R;
01454 m_robot->rootLink()->p = target_root_p + target_root_R * rel_cog - current_root_R * rel_cog;
01455 m_robot->calcForwardKinematics();
01456 current_base_rpy = hrp::rpyFromRot(m_robot->rootLink()->R);
01457 current_base_pos = m_robot->rootLink()->p;
01458 if ( DEBUGP || (is_root_rot_limit && loop%200==0) ) {
01459 std::cerr << "[" << m_profile.instance_name << "] Root rot control" << std::endl;
01460 if (is_root_rot_limit) std::cerr << "[" << m_profile.instance_name << "] Root rot limit reached!!" << std::endl;
01461 std::cerr << "[" << m_profile.instance_name << "] ref = [" << rad2deg(ref_root_rpy(0)) << " " << rad2deg(ref_root_rpy(1)) << "], "
01462 << "act = [" << rad2deg(act_base_rpy(0)) << " " << rad2deg(act_base_rpy(1)) << "], "
01463 << "cur = [" << rad2deg(current_base_rpy(0)) << " " << rad2deg(current_base_rpy(1)) << "], "
01464 << "limit = [" << rad2deg(root_rot_compensation_limit[0]) << " " << rad2deg(root_rot_compensation_limit[1]) << "][deg]" << std::endl;
01465 }
01466 };
01467
01468 void Stabilizer::calcSwingSupportLimbGain ()
01469 {
01470 for (size_t i = 0; i < stikp.size(); i++) {
01471 STIKParam& ikp = stikp[i];
01472 if (ref_contact_states[i]) {
01473
01474 ikp.support_time = std::min(3600.0, ikp.support_time+dt);
01475
01476
01477
01478 if (ikp.support_time > eefm_pos_transition_time) {
01479 ikp.swing_support_gain = (m_controlSwingSupportTime.data[i] / eefm_pos_transition_time);
01480 } else {
01481 ikp.swing_support_gain = (ikp.support_time / eefm_pos_transition_time);
01482 }
01483 ikp.swing_support_gain = std::max(0.0, std::min(1.0, ikp.swing_support_gain));
01484 } else {
01485 ikp.swing_support_gain = 0.0;
01486 ikp.support_time = 0.0;
01487 }
01488 }
01489 if (DEBUGP) {
01490 std::cerr << "[" << m_profile.instance_name << "] SwingSupportLimbGain = [";
01491 for (size_t i = 0; i < stikp.size(); i++) std::cerr << stikp[i].swing_support_gain << " ";
01492 std::cerr << "], ref_contact_states = [";
01493 for (size_t i = 0; i < stikp.size(); i++) std::cerr << ref_contact_states[i] << " ";
01494 std::cerr << "], sstime = [";
01495 for (size_t i = 0; i < stikp.size(); i++) std::cerr << m_controlSwingSupportTime.data[i] << " ";
01496 std::cerr << "], toeheel_ratio = [";
01497 for (size_t i = 0; i < stikp.size(); i++) std::cerr << toeheel_ratio[i] << " ";
01498 std::cerr << "], support_time = [";
01499 for (size_t i = 0; i < stikp.size(); i++) std::cerr << stikp[i].support_time << " ";
01500 std::cerr << "]" << std::endl;
01501 }
01502 }
01503
01504 void Stabilizer::calcTPCC() {
01505
01506
01507 hrp::Vector3 cog = m_robot->calcCM();
01508 hrp::Vector3 newcog = hrp::Vector3::Zero();
01509 hrp::Vector3 dcog(ref_cog - act_cog);
01510 hrp::Vector3 dzmp(ref_zmp - act_zmp);
01511 for (size_t i = 0; i < 2; i++) {
01512 double uu = ref_cogvel(i) - k_tpcc_p[i] * transition_smooth_gain * dzmp(i)
01513 + k_tpcc_x[i] * transition_smooth_gain * dcog(i);
01514 newcog(i) = uu * dt + cog(i);
01515 }
01516
01517 moveBasePosRotForBodyRPYControl ();
01518
01519
01520 hrp::Vector3 target_link_p[stikp.size()];
01521 hrp::Matrix33 target_link_R[stikp.size()];
01522 for (size_t i = 0; i < stikp.size(); i++) {
01523 rats::rotm3times(target_link_R[i], target_ee_R[i], stikp[i].localR.transpose());
01524 target_link_p[i] = target_ee_p[i] - target_ee_R[i] * stikp[i].localCOPPos;
01525 }
01526
01527
01528
01529 size_t max_ik_loop_count = 0;
01530 for (size_t i = 0; i < stikp.size(); i++) {
01531 if (max_ik_loop_count < stikp[i].ik_loop_count) max_ik_loop_count = stikp[i].ik_loop_count;
01532 }
01533 for (size_t jj = 0; jj < max_ik_loop_count; jj++) {
01534 hrp::Vector3 tmpcm = m_robot->calcCM();
01535 for (size_t i = 0; i < 2; i++) {
01536 m_robot->rootLink()->p(i) = m_robot->rootLink()->p(i) + 0.9 * (newcog(i) - tmpcm(i));
01537 }
01538 m_robot->calcForwardKinematics();
01539 for (size_t i = 0; i < stikp.size(); i++) {
01540 if (is_ik_enable[i]) {
01541 jpe_v[i]->calcInverseKinematics2Loop(target_link_p[i], target_link_R[i], 1.0, stikp[i].avoid_gain, stikp[i].reference_gain, &qrefv, transition_smooth_gain);
01542 }
01543 }
01544 }
01545 }
01546
01547
01548 void Stabilizer::calcEEForceMomentControl() {
01549
01550
01551
01552 m_robot->rootLink()->R = target_root_R;
01553 m_robot->rootLink()->p = target_root_p;
01554 for ( int i = 0; i < m_robot->numJoints(); i++ ) {
01555 m_robot->joint(i)->q = qrefv[i];
01556 }
01557 for (size_t i = 0; i < jpe_v.size(); i++) {
01558 if (is_ik_enable[i]) {
01559 for ( int j = 0; j < jpe_v[i]->numJoints(); j++ ){
01560 int idx = jpe_v[i]->joint(j)->jointId;
01561 m_robot->joint(idx)->q = qorg[idx];
01562 }
01563 }
01564 }
01565
01566 for (size_t i = 0; i < jpe_v.size(); i++) {
01567 if (is_ik_enable[i]) {
01568 if (jpe_v[i]->numJoints() == 7) {
01569 int idx = jpe_v[i]->joint(jpe_v[i]->numJoints() -1)->jointId;
01570 m_robot->joint(idx)->q = qrefv[idx];
01571 }
01572 }
01573 }
01574
01575
01576
01577
01578
01579 {
01580
01581 m_robot->rootLink()->R = target_root_R;
01582 m_robot->rootLink()->p = target_root_p;
01583 m_robot->calcForwardKinematics();
01584 hrp::Sensor* sen = m_robot->sensor<hrp::RateGyroSensor>("gyrometer");
01585 hrp::Matrix33 senR = sen->link->R * sen->localR;
01586 hrp::Matrix33 act_Rs(hrp::rotFromRpy(m_rpy.data.r, m_rpy.data.p, m_rpy.data.y));
01587 m_robot->rootLink()->R = act_Rs * (senR.transpose() * m_robot->rootLink()->R);
01588 m_robot->calcForwardKinematics();
01589 hrp::Vector3 foot_origin_pos;
01590 hrp::Matrix33 foot_origin_rot;
01591 calcFootOriginCoords (foot_origin_pos, foot_origin_rot);
01592
01593
01594 for (size_t i = 0; i < stikp.size(); i++) {
01595 hrp::Link* target = m_robot->link(stikp[i].target_name);
01596 stikp[i].target_ee_diff_p -= foot_origin_rot.transpose() * (target->p + target->R * stikp[i].localp - foot_origin_pos);
01597 stikp[i].target_ee_diff_r = (foot_origin_rot.transpose() * target->R * stikp[i].localR).transpose() * stikp[i].target_ee_diff_r;
01598 }
01599 }
01600
01601
01602
01603
01604
01605 moveBasePosRotForBodyRPYControl ();
01606
01607
01608 hrp::Vector3 foot_origin_pos;
01609 hrp::Matrix33 foot_origin_rot;
01610 calcFootOriginCoords (foot_origin_pos, foot_origin_rot);
01611 std::vector<hrp::Vector3> current_d_foot_pos;
01612 for (size_t i = 0; i < stikp.size(); i++)
01613 current_d_foot_pos.push_back(foot_origin_rot * stikp[i].d_foot_pos);
01614
01615
01616 calcSwingEEModification();
01617
01618
01619
01620 std::vector<hrp::Vector3> tmpp(stikp.size());
01621 std::vector<hrp::Matrix33> tmpR(stikp.size());
01622 double tmp_d_pos_z_root = 0.0;
01623 for (size_t i = 0; i < stikp.size(); i++) {
01624 if (is_ik_enable[i]) {
01625
01626 if (is_feedback_control_enable[i]) {
01627 rats::rotm3times(tmpR[i], target_ee_R[i], hrp::rotFromRpy(-1*stikp[i].ee_d_foot_rpy));
01628
01629
01630
01631 tmpp[i] = target_ee_p[i] - current_d_foot_pos[i];
01632 } else {
01633 tmpp[i] = target_ee_p[i];
01634 tmpR[i] = target_ee_R[i];
01635 }
01636
01637 rats::rotm3times(tmpR[i], tmpR[i], hrp::rotFromRpy(stikp[i].d_rpy_swing));
01638 tmpp[i] = tmpp[i] + foot_origin_rot * stikp[i].d_pos_swing;
01639 }
01640 }
01641
01642 limbStretchAvoidanceControl(tmpp ,tmpR);
01643
01644
01645 for (size_t i = 0; i < stikp.size(); i++) {
01646 if (is_ik_enable[i]) {
01647 for (size_t jj = 0; jj < stikp[i].ik_loop_count; jj++) {
01648 jpe_v[i]->calcInverseKinematics2Loop(tmpp[i], tmpR[i], 1.0, 0.001, 0.01, &qrefv, transition_smooth_gain,
01649
01650 stikp[i].localp,
01651 stikp[i].localR);
01652 }
01653 }
01654 }
01655 }
01656
01657
01658
01659
01660
01661 void Stabilizer::calcSwingEEModification ()
01662 {
01663 for (size_t i = 0; i < stikp.size(); i++) {
01664
01665 double limit_pos = 30 * 1e-3;
01666 double limit_rot = deg2rad(10);
01667 if (ref_contact_states[contact_states_index_map[stikp[i].ee_name]] || act_contact_states[contact_states_index_map[stikp[i].ee_name]]) {
01668
01669 stikp[i].d_rpy_swing = calcDampingControl(stikp[i].d_rpy_swing, stikp[i].eefm_swing_rot_time_const);
01670 stikp[i].d_pos_swing = calcDampingControl(stikp[i].d_pos_swing, stikp[i].eefm_swing_pos_time_const);
01671 stikp[i].target_ee_diff_p_filter->reset(stikp[i].d_pos_swing);
01672 stikp[i].target_ee_diff_r_filter->reset(stikp[i].d_rpy_swing);
01673 } else {
01674
01675 {
01676 hrp::Vector3 tmpdiffp = stikp[i].eefm_swing_pos_spring_gain.cwiseProduct(stikp[i].target_ee_diff_p_filter->passFilter(stikp[i].target_ee_diff_p));
01677 double lvlimit = -50 * 1e-3 * dt, uvlimit = 50 * 1e-3 * dt;
01678 hrp::Vector3 limit_by_lvlimit = stikp[i].prev_d_pos_swing + lvlimit * hrp::Vector3::Ones();
01679 hrp::Vector3 limit_by_uvlimit = stikp[i].prev_d_pos_swing + uvlimit * hrp::Vector3::Ones();
01680 stikp[i].d_pos_swing = vlimit(vlimit(tmpdiffp, -1 * limit_pos, limit_pos), limit_by_lvlimit, limit_by_uvlimit);
01681 }
01682
01683 {
01684 hrp::Vector3 tmpdiffr = stikp[i].eefm_swing_rot_spring_gain.cwiseProduct(stikp[i].target_ee_diff_r_filter->passFilter(hrp::rpyFromRot(stikp[i].target_ee_diff_r)));
01685 double lvlimit = deg2rad(-20.0*dt), uvlimit = deg2rad(20.0*dt);
01686 hrp::Vector3 limit_by_lvlimit = stikp[i].prev_d_rpy_swing + lvlimit * hrp::Vector3::Ones();
01687 hrp::Vector3 limit_by_uvlimit = stikp[i].prev_d_rpy_swing + uvlimit * hrp::Vector3::Ones();
01688 stikp[i].d_rpy_swing = vlimit(vlimit(tmpdiffr, -1 * limit_rot, limit_rot), limit_by_lvlimit, limit_by_uvlimit);
01689 }
01690 }
01691 stikp[i].prev_d_pos_swing = stikp[i].d_pos_swing;
01692 stikp[i].prev_d_rpy_swing = stikp[i].d_rpy_swing;
01693 }
01694 if (DEBUGP) {
01695 std::cerr << "[" << m_profile.instance_name << "] Swing foot control" << std::endl;
01696 for (size_t i = 0; i < stikp.size(); i++) {
01697 std::cerr << "[" << m_profile.instance_name << "] "
01698 << "d_rpy_swing (" << stikp[i].ee_name << ") = " << (stikp[i].d_rpy_swing / M_PI * 180.0).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[deg], "
01699 << "d_pos_swing (" << stikp[i].ee_name << ") = " << (stikp[i].d_pos_swing * 1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[mm]" << std::endl;
01700 }
01701 }
01702 };
01703
01704 void Stabilizer::limbStretchAvoidanceControl (const std::vector<hrp::Vector3>& ee_p, const std::vector<hrp::Matrix33>& ee_R)
01705 {
01706 double tmp_d_pos_z_root = 0.0, prev_d_pos_z_root = d_pos_z_root;
01707 if (use_limb_stretch_avoidance) {
01708 for (size_t i = 0; i < stikp.size(); i++) {
01709 if (is_ik_enable[i]) {
01710
01711 hrp::Link* parent_link = m_robot->link(stikp[i].parent_name);
01712 hrp::Vector3 targetp = (ee_p[i] - ee_R[i] * stikp[i].localR.transpose() * stikp[i].localp) - parent_link->p;
01713 double limb_length_limitation = stikp[i].max_limb_length - stikp[i].limb_length_margin;
01714 double tmp = limb_length_limitation * limb_length_limitation - targetp(0) * targetp(0) - targetp(1) * targetp(1);
01715 if (targetp.norm() > limb_length_limitation && tmp >= 0) {
01716 tmp_d_pos_z_root = std::min(tmp_d_pos_z_root, targetp(2) + std::sqrt(tmp));
01717 }
01718 }
01719 }
01720
01721 d_pos_z_root = tmp_d_pos_z_root == 0.0 ? calcDampingControl(d_pos_z_root, limb_stretch_avoidance_time_const) : tmp_d_pos_z_root;
01722 } else {
01723 d_pos_z_root = calcDampingControl(d_pos_z_root, limb_stretch_avoidance_time_const);
01724 }
01725 d_pos_z_root = vlimit(d_pos_z_root, prev_d_pos_z_root + limb_stretch_avoidance_vlimit[0], prev_d_pos_z_root + limb_stretch_avoidance_vlimit[1]);
01726 m_robot->rootLink()->p(2) += d_pos_z_root;
01727 }
01728
01729
01730
01731 double Stabilizer::calcDampingControl (const double tau_d, const double tau, const double prev_d,
01732 const double DD, const double TT)
01733 {
01734 return (1/DD * (tau_d - tau) - 1/TT * prev_d) * dt + prev_d;
01735 };
01736
01737
01738 hrp::Vector3 Stabilizer::calcDampingControl (const hrp::Vector3& prev_d, const hrp::Vector3& TT)
01739 {
01740 return (- prev_d.cwiseQuotient(TT)) * dt + prev_d;
01741 };
01742
01743
01744 double Stabilizer::calcDampingControl (const double prev_d, const double TT)
01745 {
01746 return - 1/TT * prev_d * dt + prev_d;
01747 };
01748
01749 hrp::Vector3 Stabilizer::calcDampingControl (const hrp::Vector3& tau_d, const hrp::Vector3& tau, const hrp::Vector3& prev_d,
01750 const hrp::Vector3& DD, const hrp::Vector3& TT)
01751 {
01752 return ((tau_d - tau).cwiseQuotient(DD) - prev_d.cwiseQuotient(TT)) * dt + prev_d;
01753 };
01754
01755 void Stabilizer::calcDiffFootOriginExtMoment ()
01756 {
01757
01758
01759 double mg = total_mass * eefm_gravitational_acceleration;
01760 hrp::Vector3 ref_ext_moment = hrp::Vector3(mg * ref_cog(1) - ref_total_foot_origin_moment(0),
01761 -mg * ref_cog(0) - ref_total_foot_origin_moment(1),
01762 0);
01763
01764 hrp::Vector3 act_ext_moment = hrp::Vector3(mg * act_cog(1) - act_total_foot_origin_moment(0),
01765 -mg * act_cog(0) - act_total_foot_origin_moment(1),
01766 0);
01767
01768 if ( !on_ground ) act_ext_moment = ref_ext_moment;
01769
01770 diff_foot_origin_ext_moment = ref_ext_moment - act_ext_moment;
01771 if (DEBUGP) {
01772 std::cerr << "[" << m_profile.instance_name << "] DiffStaticBalancePointOffset" << std::endl;
01773 std::cerr << "[" << m_profile.instance_name << "] "
01774 << "ref_ext_moment = " << ref_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[mm], "
01775 << "act_ext_moment = " << act_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[mm], "
01776 << "diff ext_moment = " << diff_foot_origin_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[mm]" << std::endl;
01777 }
01778 };
01779
01780
01781
01782
01783
01784
01785
01786
01787
01788
01789
01790
01791
01792
01793
01794
01795
01796
01797
01798
01799
01800
01801
01802
01803
01804
01805
01806
01807
01808
01809
01810
01811
01812
01813
01814
01815 void Stabilizer::sync_2_st ()
01816 {
01817 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm
01818 << "] Sync IDLE => ST" << std::endl;
01819 pangx_ref = pangy_ref = pangx = pangy = 0;
01820 rdx = rdy = rx = ry = 0;
01821 d_rpy[0] = d_rpy[1] = 0;
01822 pdr = hrp::Vector3::Zero();
01823 pos_ctrl = hrp::Vector3::Zero();
01824 for (size_t i = 0; i < stikp.size(); i++) {
01825 STIKParam& ikp = stikp[i];
01826 ikp.target_ee_diff_p = hrp::Vector3::Zero();
01827 ikp.target_ee_diff_r = hrp::Matrix33::Identity();
01828 ikp.d_pos_swing = ikp.prev_d_pos_swing = hrp::Vector3::Zero();
01829 ikp.d_rpy_swing = ikp.prev_d_rpy_swing = hrp::Vector3::Zero();
01830 ikp.target_ee_diff_p_filter->reset(hrp::Vector3::Zero());
01831 ikp.target_ee_diff_r_filter->reset(hrp::Vector3::Zero());
01832 ikp.d_foot_pos = ikp.ee_d_foot_pos = ikp.d_foot_rpy = ikp.ee_d_foot_rpy = hrp::Vector3::Zero();
01833 }
01834 if (on_ground) {
01835 transition_count = -1 * calcMaxTransitionCount();
01836 control_mode = MODE_ST;
01837 } else {
01838 transition_count = 0;
01839 control_mode = MODE_AIR;
01840 }
01841 }
01842
01843 void Stabilizer::sync_2_idle ()
01844 {
01845 std::cerr << "[" << m_profile.instance_name << "] [" << m_qRef.tm
01846 << "] Sync ST => IDLE" << std::endl;
01847 transition_count = calcMaxTransitionCount();
01848 for (int i = 0; i < m_robot->numJoints(); i++ ) {
01849 transition_joint_q[i] = m_robot->joint(i)->q;
01850 }
01851 }
01852
01853 void Stabilizer::startStabilizer(void)
01854 {
01855 waitSTTransition();
01856 {
01857 Guard guard(m_mutex);
01858 if ( control_mode == MODE_IDLE ) {
01859 std::cerr << "[" << m_profile.instance_name << "] " << "Start ST" << std::endl;
01860 sync_2_st();
01861 }
01862 }
01863 waitSTTransition();
01864 std::cerr << "[" << m_profile.instance_name << "] " << "Start ST DONE" << std::endl;
01865 }
01866
01867 void Stabilizer::stopStabilizer(void)
01868 {
01869 waitSTTransition();
01870 {
01871 Guard guard(m_mutex);
01872 if ( (control_mode == MODE_ST || control_mode == MODE_AIR) ) {
01873 std::cerr << "[" << m_profile.instance_name << "] " << "Stop ST" << std::endl;
01874 control_mode = (control_mode == MODE_ST) ? MODE_SYNC_TO_IDLE : MODE_IDLE;
01875 }
01876 }
01877 waitSTTransition();
01878 std::cerr << "[" << m_profile.instance_name << "] " << "Stop ST DONE" << std::endl;
01879 }
01880
01881 void Stabilizer::getParameter(OpenHRP::StabilizerService::stParam& i_stp)
01882 {
01883 std::cerr << "[" << m_profile.instance_name << "] getParameter" << std::endl;
01884 for (size_t i = 0; i < 2; i++) {
01885
01886
01887
01888
01889
01890 i_stp.k_tpcc_p[i] = k_tpcc_p[i];
01891 i_stp.k_tpcc_x[i] = k_tpcc_x[i];
01892 i_stp.k_brot_p[i] = k_brot_p[i];
01893 i_stp.k_brot_tc[i] = k_brot_tc[i];
01894 }
01895
01896
01897
01898
01899 for (size_t i = 0; i < 2; i++) {
01900 i_stp.eefm_k1[i] = eefm_k1[i];
01901 i_stp.eefm_k2[i] = eefm_k2[i];
01902 i_stp.eefm_k3[i] = eefm_k3[i];
01903 i_stp.eefm_zmp_delay_time_const[i] = eefm_zmp_delay_time_const[i];
01904 i_stp.eefm_ref_zmp_aux[i] = ref_zmp_aux(i);
01905 i_stp.eefm_body_attitude_control_time_const[i] = eefm_body_attitude_control_time_const[i];
01906 i_stp.eefm_body_attitude_control_gain[i] = eefm_body_attitude_control_gain[i];
01907 i_stp.ref_capture_point[i] = ref_cp(i);
01908 i_stp.act_capture_point[i] = act_cp(i);
01909 i_stp.cp_offset[i] = cp_offset(i);
01910 }
01911 i_stp.eefm_pos_time_const_support.length(stikp.size());
01912 i_stp.eefm_pos_damping_gain.length(stikp.size());
01913 i_stp.eefm_pos_compensation_limit.length(stikp.size());
01914 i_stp.eefm_swing_pos_spring_gain.length(stikp.size());
01915 i_stp.eefm_swing_pos_time_const.length(stikp.size());
01916 i_stp.eefm_rot_time_const.length(stikp.size());
01917 i_stp.eefm_rot_damping_gain.length(stikp.size());
01918 i_stp.eefm_rot_compensation_limit.length(stikp.size());
01919 i_stp.eefm_swing_rot_spring_gain.length(stikp.size());
01920 i_stp.eefm_swing_rot_time_const.length(stikp.size());
01921 i_stp.eefm_ee_moment_limit.length(stikp.size());
01922 i_stp.eefm_ee_forcemoment_distribution_weight.length(stikp.size());
01923 for (size_t j = 0; j < stikp.size(); j++) {
01924 i_stp.eefm_pos_damping_gain[j].length(3);
01925 i_stp.eefm_pos_time_const_support[j].length(3);
01926 i_stp.eefm_swing_pos_spring_gain[j].length(3);
01927 i_stp.eefm_swing_pos_time_const[j].length(3);
01928 i_stp.eefm_rot_damping_gain[j].length(3);
01929 i_stp.eefm_rot_time_const[j].length(3);
01930 i_stp.eefm_swing_rot_spring_gain[j].length(3);
01931 i_stp.eefm_swing_rot_time_const[j].length(3);
01932 i_stp.eefm_ee_moment_limit[j].length(3);
01933 i_stp.eefm_ee_forcemoment_distribution_weight[j].length(6);
01934 for (size_t i = 0; i < 3; i++) {
01935 i_stp.eefm_pos_damping_gain[j][i] = stikp[j].eefm_pos_damping_gain(i);
01936 i_stp.eefm_pos_time_const_support[j][i] = stikp[j].eefm_pos_time_const_support(i);
01937 i_stp.eefm_swing_pos_spring_gain[j][i] = stikp[j].eefm_swing_pos_spring_gain(i);
01938 i_stp.eefm_swing_pos_time_const[j][i] = stikp[j].eefm_swing_pos_time_const(i);
01939 i_stp.eefm_rot_damping_gain[j][i] = stikp[j].eefm_rot_damping_gain(i);
01940 i_stp.eefm_rot_time_const[j][i] = stikp[j].eefm_rot_time_const(i);
01941 i_stp.eefm_swing_rot_spring_gain[j][i] = stikp[j].eefm_swing_rot_spring_gain(i);
01942 i_stp.eefm_swing_rot_time_const[j][i] = stikp[j].eefm_swing_rot_time_const(i);
01943 i_stp.eefm_ee_moment_limit[j][i] = stikp[j].eefm_ee_moment_limit(i);
01944 i_stp.eefm_ee_forcemoment_distribution_weight[j][i] = stikp[j].eefm_ee_forcemoment_distribution_weight(i);
01945 i_stp.eefm_ee_forcemoment_distribution_weight[j][i+3] = stikp[j].eefm_ee_forcemoment_distribution_weight(i+3);
01946 }
01947 i_stp.eefm_pos_compensation_limit[j] = stikp[j].eefm_pos_compensation_limit;
01948 i_stp.eefm_rot_compensation_limit[j] = stikp[j].eefm_rot_compensation_limit;
01949 }
01950 for (size_t i = 0; i < 3; i++) {
01951 i_stp.eefm_swing_pos_damping_gain[i] = eefm_swing_pos_damping_gain(i);
01952 i_stp.eefm_swing_rot_damping_gain[i] = eefm_swing_rot_damping_gain(i);
01953 }
01954 i_stp.eefm_pos_time_const_swing = eefm_pos_time_const_swing;
01955 i_stp.eefm_pos_transition_time = eefm_pos_transition_time;
01956 i_stp.eefm_pos_margin_time = eefm_pos_margin_time;
01957 i_stp.eefm_leg_inside_margin = szd->get_leg_inside_margin();
01958 i_stp.eefm_leg_outside_margin = szd->get_leg_outside_margin();
01959 i_stp.eefm_leg_front_margin = szd->get_leg_front_margin();
01960 i_stp.eefm_leg_rear_margin = szd->get_leg_rear_margin();
01961
01962 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
01963 szd->get_vertices(support_polygon_vec);
01964 i_stp.eefm_support_polygon_vertices_sequence.length(support_polygon_vec.size());
01965 for (size_t ee_idx = 0; ee_idx < support_polygon_vec.size(); ee_idx++) {
01966 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices.length(support_polygon_vec[ee_idx].size());
01967 for (size_t v_idx = 0; v_idx < support_polygon_vec[ee_idx].size(); v_idx++) {
01968 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[0] = support_polygon_vec[ee_idx][v_idx](0);
01969 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[1] = support_polygon_vec[ee_idx][v_idx](1);
01970 }
01971 }
01972
01973 i_stp.eefm_cogvel_cutoff_freq = act_cogvel_filter->getCutOffFreq();
01974 i_stp.eefm_wrench_alpha_blending = szd->get_wrench_alpha_blending();
01975 i_stp.eefm_alpha_cutoff_freq = szd->get_alpha_cutoff_freq();
01976 i_stp.eefm_gravitational_acceleration = eefm_gravitational_acceleration;
01977 i_stp.eefm_ee_error_cutoff_freq = stikp[0].target_ee_diff_p_filter->getCutOffFreq();
01978 i_stp.eefm_use_force_difference_control = eefm_use_force_difference_control;
01979 i_stp.eefm_use_swing_damping = eefm_use_swing_damping;
01980 for (size_t i = 0; i < 3; ++i) {
01981 i_stp.eefm_swing_damping_force_thre[i] = eefm_swing_damping_force_thre[i];
01982 i_stp.eefm_swing_damping_moment_thre[i] = eefm_swing_damping_moment_thre[i];
01983 }
01984 i_stp.is_ik_enable.length(is_ik_enable.size());
01985 for (size_t i = 0; i < is_ik_enable.size(); i++) {
01986 i_stp.is_ik_enable[i] = is_ik_enable[i];
01987 }
01988 i_stp.is_feedback_control_enable.length(is_feedback_control_enable.size());
01989 for (size_t i = 0; i < is_feedback_control_enable.size(); i++) {
01990 i_stp.is_feedback_control_enable[i] = is_feedback_control_enable[i];
01991 }
01992 i_stp.is_zmp_calc_enable.length(is_zmp_calc_enable.size());
01993 for (size_t i = 0; i < is_zmp_calc_enable.size(); i++) {
01994 i_stp.is_zmp_calc_enable[i] = is_zmp_calc_enable[i];
01995 }
01996
01997 i_stp.foot_origin_offset.length(2);
01998 for (size_t i = 0; i < i_stp.foot_origin_offset.length(); i++) {
01999 i_stp.foot_origin_offset[i].length(3);
02000 i_stp.foot_origin_offset[i][0] = foot_origin_offset[i](0);
02001 i_stp.foot_origin_offset[i][1] = foot_origin_offset[i](1);
02002 i_stp.foot_origin_offset[i][2] = foot_origin_offset[i](2);
02003 }
02004 i_stp.st_algorithm = st_algorithm;
02005 i_stp.transition_time = transition_time;
02006 i_stp.cop_check_margin = cop_check_margin;
02007 for (size_t i = 0; i < cp_check_margin.size(); i++) {
02008 i_stp.cp_check_margin[i] = cp_check_margin[i];
02009 }
02010 for (size_t i = 0; i < tilt_margin.size(); i++) {
02011 i_stp.tilt_margin[i] = tilt_margin[i];
02012 }
02013 i_stp.contact_decision_threshold = contact_decision_threshold;
02014 i_stp.is_estop_while_walking = is_estop_while_walking;
02015 switch(control_mode) {
02016 case MODE_IDLE: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_IDLE; break;
02017 case MODE_AIR: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_AIR; break;
02018 case MODE_ST: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_ST; break;
02019 case MODE_SYNC_TO_IDLE: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_SYNC_TO_IDLE; break;
02020 case MODE_SYNC_TO_AIR: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_SYNC_TO_AIR; break;
02021 default: break;
02022 }
02023 i_stp.emergency_check_mode = emergency_check_mode;
02024 i_stp.end_effector_list.length(stikp.size());
02025 i_stp.use_limb_stretch_avoidance = use_limb_stretch_avoidance;
02026 i_stp.use_zmp_truncation = use_zmp_truncation;
02027 i_stp.limb_stretch_avoidance_time_const = limb_stretch_avoidance_time_const;
02028 i_stp.limb_length_margin.length(stikp.size());
02029 i_stp.detection_time_to_air = detection_count_to_air * dt;
02030 for (size_t i = 0; i < 2; i++) {
02031 i_stp.limb_stretch_avoidance_vlimit[i] = limb_stretch_avoidance_vlimit[i];
02032 i_stp.root_rot_compensation_limit[i] = root_rot_compensation_limit[i];
02033 }
02034 for (size_t i = 0; i < stikp.size(); i++) {
02035 const rats::coordinates cur_ee = rats::coordinates(stikp.at(i).localp, stikp.at(i).localR);
02036 OpenHRP::AutoBalancerService::Footstep ret_ee;
02037
02038 memcpy(ret_ee.pos, cur_ee.pos.data(), sizeof(double)*3);
02039
02040 Eigen::Quaternion<double> qt(cur_ee.rot);
02041 ret_ee.rot[0] = qt.w();
02042 ret_ee.rot[1] = qt.x();
02043 ret_ee.rot[2] = qt.y();
02044 ret_ee.rot[3] = qt.z();
02045
02046 ret_ee.leg = stikp.at(i).ee_name.c_str();
02047
02048 i_stp.end_effector_list[i] = ret_ee;
02049 i_stp.limb_length_margin[i] = stikp[i].limb_length_margin;
02050 }
02051 i_stp.ik_limb_parameters.length(jpe_v.size());
02052 for (size_t i = 0; i < jpe_v.size(); i++) {
02053 OpenHRP::StabilizerService::IKLimbParameters& ilp = i_stp.ik_limb_parameters[i];
02054 ilp.ik_optional_weight_vector.length(jpe_v[i]->numJoints());
02055 std::vector<double> ov;
02056 ov.resize(jpe_v[i]->numJoints());
02057 jpe_v[i]->getOptionalWeightVector(ov);
02058 for (size_t j = 0; j < jpe_v[i]->numJoints(); j++) {
02059 ilp.ik_optional_weight_vector[j] = ov[j];
02060 }
02061 ilp.sr_gain = jpe_v[i]->getSRGain();
02062 ilp.avoid_gain = stikp[i].avoid_gain;
02063 ilp.reference_gain = stikp[i].reference_gain;
02064 ilp.manipulability_limit = jpe_v[i]->getManipulabilityLimit();
02065 ilp.ik_loop_count = stikp[i].ik_loop_count;
02066 }
02067 };
02068
02069 void Stabilizer::setParameter(const OpenHRP::StabilizerService::stParam& i_stp)
02070 {
02071 Guard guard(m_mutex);
02072 std::cerr << "[" << m_profile.instance_name << "] setParameter" << std::endl;
02073 for (size_t i = 0; i < 2; i++) {
02074 k_tpcc_p[i] = i_stp.k_tpcc_p[i];
02075 k_tpcc_x[i] = i_stp.k_tpcc_x[i];
02076 k_brot_p[i] = i_stp.k_brot_p[i];
02077 k_brot_tc[i] = i_stp.k_brot_tc[i];
02078 }
02079 std::cerr << "[" << m_profile.instance_name << "] TPCC" << std::endl;
02080 std::cerr << "[" << m_profile.instance_name << "] k_tpcc_p = [" << k_tpcc_p[0] << ", " << k_tpcc_p[1] << "], k_tpcc_x = [" << k_tpcc_x[0] << ", " << k_tpcc_x[1] << "], k_brot_p = [" << k_brot_p[0] << ", " << k_brot_p[1] << "], k_brot_tc = [" << k_brot_tc[0] << ", " << k_brot_tc[1] << "]" << std::endl;
02081
02082
02083
02084
02085
02086
02087
02088
02089
02090
02091
02092
02093
02094
02095
02096
02097 std::cerr << "[" << m_profile.instance_name << "] EEFM" << std::endl;
02098 for (size_t i = 0; i < 2; i++) {
02099 eefm_k1[i] = i_stp.eefm_k1[i];
02100 eefm_k2[i] = i_stp.eefm_k2[i];
02101 eefm_k3[i] = i_stp.eefm_k3[i];
02102 eefm_zmp_delay_time_const[i] = i_stp.eefm_zmp_delay_time_const[i];
02103 ref_zmp_aux(i) = i_stp.eefm_ref_zmp_aux[i];
02104 eefm_body_attitude_control_gain[i] = i_stp.eefm_body_attitude_control_gain[i];
02105 eefm_body_attitude_control_time_const[i] = i_stp.eefm_body_attitude_control_time_const[i];
02106 ref_cp(i) = i_stp.ref_capture_point[i];
02107 act_cp(i) = i_stp.act_capture_point[i];
02108 cp_offset(i) = i_stp.cp_offset[i];
02109 }
02110 bool is_damping_parameter_ok = true;
02111 if ( i_stp.eefm_pos_damping_gain.length () == stikp.size() &&
02112 i_stp.eefm_pos_time_const_support.length () == stikp.size() &&
02113 i_stp.eefm_pos_compensation_limit.length () == stikp.size() &&
02114 i_stp.eefm_swing_pos_spring_gain.length () == stikp.size() &&
02115 i_stp.eefm_swing_pos_time_const.length () == stikp.size() &&
02116 i_stp.eefm_rot_damping_gain.length () == stikp.size() &&
02117 i_stp.eefm_rot_time_const.length () == stikp.size() &&
02118 i_stp.eefm_rot_compensation_limit.length () == stikp.size() &&
02119 i_stp.eefm_swing_rot_spring_gain.length () == stikp.size() &&
02120 i_stp.eefm_swing_rot_time_const.length () == stikp.size() &&
02121 i_stp.eefm_ee_moment_limit.length () == stikp.size() &&
02122 i_stp.eefm_ee_forcemoment_distribution_weight.length () == stikp.size()) {
02123 is_damping_parameter_ok = true;
02124 for (size_t j = 0; j < stikp.size(); j++) {
02125 for (size_t i = 0; i < 3; i++) {
02126 stikp[j].eefm_pos_damping_gain(i) = i_stp.eefm_pos_damping_gain[j][i];
02127 stikp[j].eefm_pos_time_const_support(i) = i_stp.eefm_pos_time_const_support[j][i];
02128 stikp[j].eefm_swing_pos_spring_gain(i) = i_stp.eefm_swing_pos_spring_gain[j][i];
02129 stikp[j].eefm_swing_pos_time_const(i) = i_stp.eefm_swing_pos_time_const[j][i];
02130 stikp[j].eefm_rot_damping_gain(i) = i_stp.eefm_rot_damping_gain[j][i];
02131 stikp[j].eefm_rot_time_const(i) = i_stp.eefm_rot_time_const[j][i];
02132 stikp[j].eefm_swing_rot_spring_gain(i) = i_stp.eefm_swing_rot_spring_gain[j][i];
02133 stikp[j].eefm_swing_rot_time_const(i) = i_stp.eefm_swing_rot_time_const[j][i];
02134 stikp[j].eefm_ee_moment_limit(i) = i_stp.eefm_ee_moment_limit[j][i];
02135 stikp[j].eefm_ee_forcemoment_distribution_weight(i) = i_stp.eefm_ee_forcemoment_distribution_weight[j][i];
02136 stikp[j].eefm_ee_forcemoment_distribution_weight(i+3) = i_stp.eefm_ee_forcemoment_distribution_weight[j][i+3];
02137 }
02138 stikp[j].eefm_pos_compensation_limit = i_stp.eefm_pos_compensation_limit[j];
02139 stikp[j].eefm_rot_compensation_limit = i_stp.eefm_rot_compensation_limit[j];
02140 }
02141 } else {
02142 is_damping_parameter_ok = false;
02143 }
02144 for (size_t i = 0; i < 3; i++) {
02145 eefm_swing_pos_damping_gain(i) = i_stp.eefm_swing_pos_damping_gain[i];
02146 eefm_swing_rot_damping_gain(i) = i_stp.eefm_swing_rot_damping_gain[i];
02147 }
02148 eefm_pos_time_const_swing = i_stp.eefm_pos_time_const_swing;
02149 eefm_pos_transition_time = i_stp.eefm_pos_transition_time;
02150 eefm_pos_margin_time = i_stp.eefm_pos_margin_time;
02151 szd->set_leg_inside_margin(i_stp.eefm_leg_inside_margin);
02152 szd->set_leg_outside_margin(i_stp.eefm_leg_outside_margin);
02153 szd->set_leg_front_margin(i_stp.eefm_leg_front_margin);
02154 szd->set_leg_rear_margin(i_stp.eefm_leg_rear_margin);
02155 szd->set_vertices_from_margin_params();
02156
02157 if (i_stp.eefm_support_polygon_vertices_sequence.length() != stikp.size()) {
02158 std::cerr << "[" << m_profile.instance_name << "] eefm_support_polygon_vertices_sequence cannot be set. Length " << i_stp.eefm_support_polygon_vertices_sequence.length() << " != " << stikp.size() << std::endl;
02159 } else {
02160 std::cerr << "[" << m_profile.instance_name << "] eefm_support_polygon_vertices_sequence set" << std::endl;
02161 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
02162 for (size_t ee_idx = 0; ee_idx < i_stp.eefm_support_polygon_vertices_sequence.length(); ee_idx++) {
02163 std::vector<Eigen::Vector2d> tvec;
02164 for (size_t v_idx = 0; v_idx < i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices.length(); v_idx++) {
02165 tvec.push_back(Eigen::Vector2d(i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[0],
02166 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[1]));
02167 }
02168 support_polygon_vec.push_back(tvec);
02169 }
02170 szd->set_vertices(support_polygon_vec);
02171 szd->print_vertices(std::string(m_profile.instance_name));
02172 }
02173 eefm_use_force_difference_control = i_stp.eefm_use_force_difference_control;
02174 eefm_use_swing_damping = i_stp.eefm_use_swing_damping;
02175 for (size_t i = 0; i < 3; ++i) {
02176 eefm_swing_damping_force_thre[i] = i_stp.eefm_swing_damping_force_thre[i];
02177 eefm_swing_damping_moment_thre[i] = i_stp.eefm_swing_damping_moment_thre[i];
02178 }
02179 act_cogvel_filter->setCutOffFreq(i_stp.eefm_cogvel_cutoff_freq);
02180 szd->set_wrench_alpha_blending(i_stp.eefm_wrench_alpha_blending);
02181 szd->set_alpha_cutoff_freq(i_stp.eefm_alpha_cutoff_freq);
02182 eefm_gravitational_acceleration = i_stp.eefm_gravitational_acceleration;
02183 for (size_t i = 0; i < stikp.size(); i++) {
02184 stikp[i].target_ee_diff_p_filter->setCutOffFreq(i_stp.eefm_ee_error_cutoff_freq);
02185 stikp[i].target_ee_diff_r_filter->setCutOffFreq(i_stp.eefm_ee_error_cutoff_freq);
02186 stikp[i].limb_length_margin = i_stp.limb_length_margin[i];
02187 }
02188 setBoolSequenceParam(is_ik_enable, i_stp.is_ik_enable, std::string("is_ik_enable"));
02189 setBoolSequenceParamWithCheckContact(is_feedback_control_enable, i_stp.is_feedback_control_enable, std::string("is_feedback_control_enable"));
02190 setBoolSequenceParam(is_zmp_calc_enable, i_stp.is_zmp_calc_enable, std::string("is_zmp_calc_enable"));
02191 emergency_check_mode = i_stp.emergency_check_mode;
02192
02193 transition_time = i_stp.transition_time;
02194 cop_check_margin = i_stp.cop_check_margin;
02195 for (size_t i = 0; i < cp_check_margin.size(); i++) {
02196 cp_check_margin[i] = i_stp.cp_check_margin[i];
02197 }
02198 szd->set_vertices_from_margin_params(cp_check_margin);
02199 for (size_t i = 0; i < tilt_margin.size(); i++) {
02200 tilt_margin[i] = i_stp.tilt_margin[i];
02201 }
02202 contact_decision_threshold = i_stp.contact_decision_threshold;
02203 is_estop_while_walking = i_stp.is_estop_while_walking;
02204 use_limb_stretch_avoidance = i_stp.use_limb_stretch_avoidance;
02205 use_zmp_truncation = i_stp.use_zmp_truncation;
02206 limb_stretch_avoidance_time_const = i_stp.limb_stretch_avoidance_time_const;
02207 for (size_t i = 0; i < 2; i++) {
02208 limb_stretch_avoidance_vlimit[i] = i_stp.limb_stretch_avoidance_vlimit[i];
02209 root_rot_compensation_limit[i] = i_stp.root_rot_compensation_limit[i];
02210 }
02211 detection_count_to_air = static_cast<int>(i_stp.detection_time_to_air / dt);
02212 if (control_mode == MODE_IDLE) {
02213 for (size_t i = 0; i < i_stp.end_effector_list.length(); i++) {
02214 std::vector<STIKParam>::iterator it = std::find_if(stikp.begin(), stikp.end(), (&boost::lambda::_1->* &std::vector<STIKParam>::value_type::ee_name == std::string(i_stp.end_effector_list[i].leg)));
02215 memcpy(it->localp.data(), i_stp.end_effector_list[i].pos, sizeof(double)*3);
02216 it->localR = (Eigen::Quaternion<double>(i_stp.end_effector_list[i].rot[0], i_stp.end_effector_list[i].rot[1], i_stp.end_effector_list[i].rot[2], i_stp.end_effector_list[i].rot[3])).normalized().toRotationMatrix();
02217 }
02218 } else {
02219 std::cerr << "[" << m_profile.instance_name << "] cannot change end-effectors except during MODE_IDLE" << std::endl;
02220 }
02221 for (std::vector<STIKParam>::const_iterator it = stikp.begin(); it != stikp.end(); it++) {
02222 std::cerr << "[" << m_profile.instance_name << "] End Effector [" << it->ee_name << "]" << std::endl;
02223 std::cerr << "[" << m_profile.instance_name << "] localpos = " << it->localp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[m]" << std::endl;
02224 std::cerr << "[" << m_profile.instance_name << "] localR = " << it->localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "", " [", "]")) << std::endl;
02225 }
02226 if (i_stp.foot_origin_offset.length () != 2) {
02227 std::cerr << "[" << m_profile.instance_name << "] foot_origin_offset cannot be set. Length " << i_stp.foot_origin_offset.length() << " != " << 2 << std::endl;
02228 } else if (control_mode != MODE_IDLE) {
02229 std::cerr << "[" << m_profile.instance_name << "] foot_origin_offset cannot be set. Current control_mode is " << control_mode << std::endl;
02230 } else {
02231 for (size_t i = 0; i < i_stp.foot_origin_offset.length(); i++) {
02232 foot_origin_offset[i](0) = i_stp.foot_origin_offset[i][0];
02233 foot_origin_offset[i](1) = i_stp.foot_origin_offset[i][1];
02234 foot_origin_offset[i](2) = i_stp.foot_origin_offset[i][2];
02235 }
02236 }
02237 std::cerr << "[" << m_profile.instance_name << "] foot_origin_offset is ";
02238 for (size_t i = 0; i < 2; i++) {
02239 std::cerr << foot_origin_offset[i].format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"));
02240 }
02241 std::cerr << "[m]" << std::endl;
02242 std::cerr << "[" << m_profile.instance_name << "] eefm_k1 = [" << eefm_k1[0] << ", " << eefm_k1[1] << "], eefm_k2 = [" << eefm_k2[0] << ", " << eefm_k2[1] << "], eefm_k3 = [" << eefm_k3[0] << ", " << eefm_k3[1] << "]" << std::endl;
02243 std::cerr << "[" << m_profile.instance_name << "] eefm_zmp_delay_time_const = [" << eefm_zmp_delay_time_const[0] << ", " << eefm_zmp_delay_time_const[1] << "][s], eefm_ref_zmp_aux = [" << ref_zmp_aux(0) << ", " << ref_zmp_aux(1) << "][m]" << std::endl;
02244 std::cerr << "[" << m_profile.instance_name << "] eefm_body_attitude_control_gain = [" << eefm_body_attitude_control_gain[0] << ", " << eefm_body_attitude_control_gain[1] << "], eefm_body_attitude_control_time_const = [" << eefm_body_attitude_control_time_const[0] << ", " << eefm_body_attitude_control_time_const[1] << "][s]" << std::endl;
02245 if (is_damping_parameter_ok) {
02246 for (size_t j = 0; j < stikp.size(); j++) {
02247 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[j].ee_name << "] eefm_rot_damping_gain = "
02248 << stikp[j].eefm_rot_damping_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"))
02249 << ", eefm_rot_time_const = "
02250 << stikp[j].eefm_rot_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"))
02251 << "[s]" << std::endl;
02252 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[j].ee_name << "] eefm_pos_damping_gain = "
02253 << stikp[j].eefm_pos_damping_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"))
02254 << ", eefm_pos_time_const_support = "
02255 << stikp[j].eefm_pos_time_const_support.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]"))
02256 << "[s]" << std::endl;
02257 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[j].ee_name << "] "
02258 << "eefm_pos_compensation_limit = " << stikp[j].eefm_pos_compensation_limit << "[m], "
02259 << "eefm_rot_compensation_limit = " << stikp[j].eefm_rot_compensation_limit << "[rad], "
02260 << "eefm_ee_moment_limit = " << stikp[j].eefm_ee_moment_limit.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "[Nm]" << std::endl;
02261 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[j].ee_name << "] "
02262 << "eefm_swing_pos_spring_gain = " << stikp[j].eefm_swing_pos_spring_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << ", "
02263 << "eefm_swing_pos_time_const = " << stikp[j].eefm_swing_pos_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << ", "
02264 << "eefm_swing_rot_spring_gain = " << stikp[j].eefm_swing_rot_spring_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << ", "
02265 << "eefm_swing_pos_time_const = " << stikp[j].eefm_swing_pos_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << ", "
02266 << std::endl;
02267 std::cerr << "[" << m_profile.instance_name << "] [" << stikp[j].ee_name << "] "
02268 << "eefm_ee_forcemoment_distribution_weight = " << stikp[j].eefm_ee_forcemoment_distribution_weight.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", " [", "]")) << "" << std::endl;
02269 }
02270 } else {
02271 std::cerr << "[" << m_profile.instance_name << "] eefm damping parameters cannot be set because of invalid param." << std::endl;
02272 }
02273 std::cerr << "[" << m_profile.instance_name << "] eefm_pos_transition_time = " << eefm_pos_transition_time << "[s], eefm_pos_margin_time = " << eefm_pos_margin_time << "[s] eefm_pos_time_const_swing = " << eefm_pos_time_const_swing << "[s]" << std::endl;
02274 std::cerr << "[" << m_profile.instance_name << "] cogvel_cutoff_freq = " << act_cogvel_filter->getCutOffFreq() << "[Hz]" << std::endl;
02275 szd->print_params(std::string(m_profile.instance_name));
02276 std::cerr << "[" << m_profile.instance_name << "] eefm_gravitational_acceleration = " << eefm_gravitational_acceleration << "[m/s^2], eefm_use_force_difference_control = " << (eefm_use_force_difference_control? "true":"false") << ", eefm_use_swing_damping = " << (eefm_use_swing_damping? "true":"false") << std::endl;
02277 std::cerr << "[" << m_profile.instance_name << "] eefm_ee_error_cutoff_freq = " << stikp[0].target_ee_diff_p_filter->getCutOffFreq() << "[Hz]" << std::endl;
02278 std::cerr << "[" << m_profile.instance_name << "] COMMON" << std::endl;
02279 if (control_mode == MODE_IDLE) {
02280 st_algorithm = i_stp.st_algorithm;
02281 std::cerr << "[" << m_profile.instance_name << "] st_algorithm changed to [" << getStabilizerAlgorithmString(st_algorithm) << "]" << std::endl;
02282 } else {
02283 std::cerr << "[" << m_profile.instance_name << "] st_algorithm cannot be changed to [" << getStabilizerAlgorithmString(st_algorithm) << "] during MODE_AIR or MODE_ST." << std::endl;
02284 }
02285 std::cerr << "[" << m_profile.instance_name << "] emergency_check_mode changed to [" << (emergency_check_mode == OpenHRP::StabilizerService::NO_CHECK?"NO_CHECK": (emergency_check_mode == OpenHRP::StabilizerService::COP?"COP":"CP") ) << "]" << std::endl;
02286 std::cerr << "[" << m_profile.instance_name << "] transition_time = " << transition_time << "[s]" << std::endl;
02287 std::cerr << "[" << m_profile.instance_name << "] cop_check_margin = " << cop_check_margin << "[m], "
02288 << "cp_check_margin = [" << cp_check_margin[0] << ", " << cp_check_margin[1] << ", " << cp_check_margin[2] << ", " << cp_check_margin[3] << "] [m], "
02289 << "tilt_margin = [" << tilt_margin[0] << ", " << tilt_margin[1] << "] [rad]" << std::endl;
02290 std::cerr << "[" << m_profile.instance_name << "] contact_decision_threshold = " << contact_decision_threshold << "[N], detection_time_to_air = " << detection_count_to_air * dt << "[s]" << std::endl;
02291 std::cerr << "[" << m_profile.instance_name << "] root_rot_compensation_limit = [" << root_rot_compensation_limit[0] << " " << root_rot_compensation_limit[1] << "][rad]" << std::endl;
02292
02293 std::cerr << "[" << m_profile.instance_name << "] IK limb parameters" << std::endl;
02294 bool is_ik_limb_parameter_valid_length = true;
02295 if (i_stp.ik_limb_parameters.length() != jpe_v.size()) {
02296 is_ik_limb_parameter_valid_length = false;
02297 std::cerr << "[" << m_profile.instance_name << "] ik_limb_parameters invalid length! Cannot be set. (input = " << i_stp.ik_limb_parameters.length() << ", desired = " << jpe_v.size() << ")" << std::endl;
02298 } else {
02299 for (size_t i = 0; i < jpe_v.size(); i++) {
02300 if (jpe_v[i]->numJoints() != i_stp.ik_limb_parameters[i].ik_optional_weight_vector.length())
02301 is_ik_limb_parameter_valid_length = false;
02302 }
02303 if (is_ik_limb_parameter_valid_length) {
02304 for (size_t i = 0; i < jpe_v.size(); i++) {
02305 const OpenHRP::StabilizerService::IKLimbParameters& ilp = i_stp.ik_limb_parameters[i];
02306 std::vector<double> ov;
02307 ov.resize(jpe_v[i]->numJoints());
02308 for (size_t j = 0; j < jpe_v[i]->numJoints(); j++) {
02309 ov[j] = ilp.ik_optional_weight_vector[j];
02310 }
02311 jpe_v[i]->setOptionalWeightVector(ov);
02312 jpe_v[i]->setSRGain(ilp.sr_gain);
02313 stikp[i].avoid_gain = ilp.avoid_gain;
02314 stikp[i].reference_gain = ilp.reference_gain;
02315 jpe_v[i]->setManipulabilityLimit(ilp.manipulability_limit);
02316 stikp[i].ik_loop_count = ilp.ik_loop_count;
02317 }
02318 } else {
02319 std::cerr << "[" << m_profile.instance_name << "] ik_optional_weight_vector invalid length! Cannot be set. (input = [";
02320 for (size_t i = 0; i < jpe_v.size(); i++) {
02321 std::cerr << i_stp.ik_limb_parameters[i].ik_optional_weight_vector.length() << ", ";
02322 }
02323 std::cerr << "], desired = [";
02324 for (size_t i = 0; i < jpe_v.size(); i++) {
02325 std::cerr << jpe_v[i]->numJoints() << ", ";
02326 }
02327 std::cerr << "])" << std::endl;
02328 }
02329 }
02330 if (is_ik_limb_parameter_valid_length) {
02331 std::cerr << "[" << m_profile.instance_name << "] ik_optional_weight_vectors = ";
02332 for (size_t i = 0; i < jpe_v.size(); i++) {
02333 std::vector<double> ov;
02334 ov.resize(jpe_v[i]->numJoints());
02335 jpe_v[i]->getOptionalWeightVector(ov);
02336 std::cerr << "[";
02337 for (size_t j = 0; j < jpe_v[i]->numJoints(); j++) {
02338 std::cerr << ov[j] << " ";
02339 }
02340 std::cerr << "]";
02341 }
02342 std::cerr << std::endl;
02343 std::cerr << "[" << m_profile.instance_name << "] sr_gains = [";
02344 for (size_t i = 0; i < jpe_v.size(); i++) {
02345 std::cerr << jpe_v[i]->getSRGain() << ", ";
02346 }
02347 std::cerr << "]" << std::endl;
02348 std::cerr << "[" << m_profile.instance_name << "] avoid_gains = [";
02349 for (size_t i = 0; i < stikp.size(); i++) {
02350 std::cerr << stikp[i].avoid_gain << ", ";
02351 }
02352 std::cerr << "]" << std::endl;
02353 std::cerr << "[" << m_profile.instance_name << "] reference_gains = [";
02354 for (size_t i = 0; i < stikp.size(); i++) {
02355 std::cerr << stikp[i].reference_gain << ", ";
02356 }
02357 std::cerr << "]" << std::endl;
02358 std::cerr << "[" << m_profile.instance_name << "] manipulability_limits = [";
02359 for (size_t i = 0; i < jpe_v.size(); i++) {
02360 std::cerr << jpe_v[i]->getManipulabilityLimit() << ", ";
02361 }
02362 std::cerr << "]" << std::endl;
02363 std::cerr << "[" << m_profile.instance_name << "] ik_loop_count = [";
02364 for (size_t i = 0; i < stikp.size(); i++) {
02365 std::cerr << stikp[i].ik_loop_count << ", ";
02366 }
02367 std::cerr << "]" << std::endl;
02368 }
02369 }
02370
02371 std::string Stabilizer::getStabilizerAlgorithmString (OpenHRP::StabilizerService::STAlgorithm _st_algorithm)
02372 {
02373 switch (_st_algorithm) {
02374 case OpenHRP::StabilizerService::TPCC:
02375 return "TPCC";
02376 case OpenHRP::StabilizerService::EEFM:
02377 return "EEFM";
02378 case OpenHRP::StabilizerService::EEFMQP:
02379 return "EEFMQP";
02380 case OpenHRP::StabilizerService::EEFMQPCOP:
02381 return "EEFMQPCOP";
02382 case OpenHRP::StabilizerService::EEFMQPCOP2:
02383 return "EEFMQPCOP2";
02384 default:
02385 return "";
02386 }
02387 };
02388
02389 void Stabilizer::setBoolSequenceParam (std::vector<bool>& st_bool_values, const OpenHRP::StabilizerService::BoolSequence& output_bool_values, const std::string& prop_name)
02390 {
02391 std::vector<bool> prev_values;
02392 prev_values.resize(st_bool_values.size());
02393 copy (st_bool_values.begin(), st_bool_values.end(), prev_values.begin());
02394 if (st_bool_values.size() != output_bool_values.length()) {
02395 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " cannot be set. Length " << st_bool_values.size() << " != " << output_bool_values.length() << std::endl;
02396 } else if ( (control_mode != MODE_IDLE) ) {
02397 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " cannot be set. Current control_mode is " << control_mode << std::endl;
02398 } else {
02399 for (size_t i = 0; i < st_bool_values.size(); i++) {
02400 st_bool_values[i] = output_bool_values[i];
02401 }
02402 }
02403 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " is ";
02404 for (size_t i = 0; i < st_bool_values.size(); i++) {
02405 std::cerr <<"[" << st_bool_values[i] << "]";
02406 }
02407 std::cerr << "(set = ";
02408 for (size_t i = 0; i < output_bool_values.length(); i++) {
02409 std::cerr <<"[" << output_bool_values[i] << "]";
02410 }
02411 std::cerr << ", prev = ";
02412 for (size_t i = 0; i < prev_values.size(); i++) {
02413 std::cerr <<"[" << prev_values[i] << "]";
02414 }
02415 std::cerr << ")" << std::endl;
02416 };
02417
02418 void Stabilizer::setBoolSequenceParamWithCheckContact (std::vector<bool>& st_bool_values, const OpenHRP::StabilizerService::BoolSequence& output_bool_values, const std::string& prop_name)
02419 {
02420 std::vector<bool> prev_values;
02421 prev_values.resize(st_bool_values.size());
02422 copy (st_bool_values.begin(), st_bool_values.end(), prev_values.begin());
02423 if (st_bool_values.size() != output_bool_values.length()) {
02424 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " cannot be set. Length " << st_bool_values.size() << " != " << output_bool_values.length() << std::endl;
02425 } else if ( control_mode == MODE_IDLE ) {
02426 for (size_t i = 0; i < st_bool_values.size(); i++) {
02427 st_bool_values[i] = output_bool_values[i];
02428 }
02429 } else {
02430 std::vector<size_t> failed_indices;
02431 for (size_t i = 0; i < st_bool_values.size(); i++) {
02432 if ( (st_bool_values[i] != output_bool_values[i]) ) {
02433 if (!ref_contact_states[i] ) {
02434 st_bool_values[i] = output_bool_values[i];
02435 } else {
02436 failed_indices.push_back(i);
02437 }
02438 }
02439 }
02440 if (failed_indices.size() > 0) {
02441 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " cannot be set partially. failed_indices is [";
02442 for (size_t i = 0; i < failed_indices.size(); i++) {
02443 std::cerr << failed_indices[i] << " ";
02444 }
02445 std::cerr << "]" << std::endl;
02446 }
02447 }
02448 std::cerr << "[" << m_profile.instance_name << "] " << prop_name << " is ";
02449 for (size_t i = 0; i < st_bool_values.size(); i++) {
02450 std::cerr <<"[" << st_bool_values[i] << "]";
02451 }
02452 std::cerr << "(set = ";
02453 for (size_t i = 0; i < output_bool_values.length(); i++) {
02454 std::cerr <<"[" << output_bool_values[i] << "]";
02455 }
02456 std::cerr << ", prev = ";
02457 for (size_t i = 0; i < prev_values.size(); i++) {
02458 std::cerr <<"[" << prev_values[i] << "]";
02459 }
02460 std::cerr << ")" << std::endl;
02461 };
02462
02463 void Stabilizer::waitSTTransition()
02464 {
02465
02466
02467
02468 bool flag = (control_mode == MODE_SYNC_TO_AIR || control_mode == MODE_SYNC_TO_IDLE);
02469 while (transition_count != 0 ||
02470 (flag ? !(control_mode == MODE_IDLE || control_mode == MODE_AIR) : false) ) {
02471 usleep(10);
02472 flag = (control_mode == MODE_SYNC_TO_AIR || control_mode == MODE_SYNC_TO_IDLE);
02473 }
02474 usleep(10);
02475 }
02476
02477 double Stabilizer::vlimit(double value, double llimit_value, double ulimit_value)
02478 {
02479 if (value > ulimit_value) {
02480 return ulimit_value;
02481 } else if (value < llimit_value) {
02482 return llimit_value;
02483 }
02484 return value;
02485 }
02486
02487 hrp::Vector3 Stabilizer::vlimit(const hrp::Vector3& value, double llimit_value, double ulimit_value)
02488 {
02489 hrp::Vector3 ret;
02490 for (size_t i = 0; i < 3; i++) {
02491 if (value(i) > ulimit_value) {
02492 ret(i) = ulimit_value;
02493 } else if (value(i) < llimit_value) {
02494 ret(i) = llimit_value;
02495 } else {
02496 ret(i) = value(i);
02497 }
02498 }
02499 return ret;
02500 }
02501
02502 hrp::Vector3 Stabilizer::vlimit(const hrp::Vector3& value, const hrp::Vector3& limit_value)
02503 {
02504 hrp::Vector3 ret;
02505 for (size_t i = 0; i < 3; i++) {
02506 if (value(i) > limit_value(i)) {
02507 ret(i) = limit_value(i);
02508 } else if (value(i) < -1 * limit_value(i)) {
02509 ret(i) = -1 * limit_value(i);
02510 } else {
02511 ret(i) = value(i);
02512 }
02513 }
02514 return ret;
02515 }
02516
02517 hrp::Vector3 Stabilizer::vlimit(const hrp::Vector3& value, const hrp::Vector3& llimit_value, const hrp::Vector3& ulimit_value)
02518 {
02519 hrp::Vector3 ret;
02520 for (size_t i = 0; i < 3; i++) {
02521 if (value(i) > ulimit_value(i)) {
02522 ret(i) = ulimit_value(i);
02523 } else if (value(i) < llimit_value(i)) {
02524 ret(i) = llimit_value(i);
02525 } else {
02526 ret(i) = value(i);
02527 }
02528 }
02529 return ret;
02530 }
02531
02532 static double switching_inpact_absorber(double force, double lower_th, double upper_th)
02533 {
02534 double gradient, intercept;
02535 if (force < lower_th) {
02536 return 0;
02537 } else if (force > upper_th) {
02538 return 1;
02539 } else {
02540 gradient = 1.0 / (upper_th - lower_th);
02541 intercept = -lower_th * gradient;
02542 return gradient * force + intercept;
02543 }
02544 }
02545
02546 void Stabilizer::calcRUNST() {
02547 if ( m_robot->numJoints() == m_qRef.data.length() ) {
02548 std::vector<std::string> target_name;
02549 target_name.push_back("L_ANKLE_R");
02550 target_name.push_back("R_ANKLE_R");
02551
02552 double angvelx_ref;
02553 double angvely_ref;
02554
02555
02556 double angvelx = (m_rpy.data.r - pangx)/dt;
02557 double angvely = (m_rpy.data.r - pangy)/dt;
02558 pangx = m_rpy.data.r;
02559 pangy = m_rpy.data.p;
02560
02561
02562 for ( int i = 0; i < m_robot->numJoints(); i++ ){
02563 qorg[i] = m_robot->joint(i)->q;
02564 m_robot->joint(i)->q = m_qRef.data[i];
02565 qrefv[i] = m_qRef.data[i];
02566 }
02567
02568 double orgjq = m_robot->joint(m_robot->link("L_ANKLE_P")->jointId)->q;
02569
02570 m_robot->rootLink()->p = hrp::Vector3(0,0,0);
02571
02572 m_robot->calcForwardKinematics();
02573 hrp::Vector3 target_root_p = m_robot->rootLink()->p;
02574 hrp::Matrix33 target_root_R = m_robot->rootLink()->R;
02575 hrp::Vector3 target_foot_p[2];
02576 hrp::Matrix33 target_foot_R[2];
02577 for (size_t i = 0; i < 2; i++) {
02578 target_foot_p[i] = m_robot->link(target_name[i])->p;
02579 target_foot_R[i] = m_robot->link(target_name[i])->R;
02580 }
02581 hrp::Vector3 target_fm = (m_robot->link(target_name[0])->p + m_robot->link(target_name[1])->p)/2;
02582
02583 hrp::Vector3 org_cm = m_robot->rootLink()->R.transpose() * (target_fm - m_robot->rootLink()->p);
02584
02585
02586 if ( ( m_wrenches[1].data.length() > 0 && m_wrenches[0].data.length() > 0 )
02587
02588 ) {
02589
02590 for ( int i = 0; i < m_robot->numJoints(); i++ ) {
02591 m_robot->joint(i)->q = qorg[i];
02592 }
02593
02594 double rddx;
02595 double rddy;
02596 rdx += rddx * dt;
02597 rx += rdx * dt;
02598 rdy += rddy * dt;
02599 ry += rdy * dt;
02600
02601
02602
02603
02604
02605
02606
02607
02608
02609
02610 hrp::Vector3 root_p_s;
02611 hrp::Matrix33 root_R_s;
02612 rats::rotm3times(root_R_s, hrp::rotFromRpy(rx, ry, 0), target_root_R);
02613 if (DEBUGP2) {
02614 hrp::Vector3 tmp = hrp::rpyFromRot(root_R_s);
02615 std::cerr << "RPY2 " << tmp(0) << " " << tmp(1) << std::endl;
02616 }
02617 root_p_s = target_root_p + target_root_R * org_cm - root_R_s * org_cm;
02618
02619
02620 m_robot->rootLink()->R = root_R_s;
02621 m_robot->rootLink()->p = root_p_s;
02622 if (DEBUGP2) {
02623 std::cerr << " rp " << root_p_s[0] << " " << root_p_s[1] << " " << root_p_s[2] << std::endl;
02624 }
02625 m_robot->calcForwardKinematics();
02626
02627 hrp::Vector3 current_fm = (m_robot->link(target_name[0])->p + m_robot->link(target_name[1])->p)/2;
02628
02629
02630 hrp::Vector3 dr = target_fm - current_fm;
02631
02632 hrp::Vector3 dr_vel = (dr - pdr)/dt;
02633 pdr = dr;
02634 double tau_y = - m_torque_k[0] * dr(0) - m_torque_d[0] * dr_vel(0);
02635 double tau_x = m_torque_k[1] * dr(1) + m_torque_d[1] * dr_vel(1);
02636 if (DEBUGP2) {
02637 dr*=1e3;
02638 dr_vel*=1e3;
02639 std::cerr << "dr " << dr(0) << " " << dr(1) << " " << dr_vel(0) << " " << dr_vel(1) << std::endl;
02640 std::cerr << "tau_x " << tau_x << std::endl;
02641 std::cerr << "tau_y " << tau_y << std::endl;
02642 }
02643
02644 double gamma = 0.5;
02645 double tau_xl[2];
02646 double tau_yl[2];
02647 double xfront = 0.125;
02648 double xrear = 0.1;
02649 double yin = 0.02;
02650 double yout = 0.15;
02651 double mg = m_robot->totalMass() * 9.8 * 0.9;
02652 double tq_y_ulimit = mg * xrear;
02653 double tq_y_llimit = -1 * mg * xfront;
02654 double tq_x_ulimit = mg * yout;
02655 double tq_x_llimit = mg * yin;
02656
02657 tau_xl[0] = gamma * tau_x;
02658 tau_yl[0] = gamma * tau_y;
02659 tau_xl[0] = vlimit(tau_xl[0], tq_x_llimit, tq_x_ulimit);
02660 tau_yl[0] = vlimit(tau_yl[0], tq_y_llimit, tq_y_ulimit);
02661
02662 tau_xl[1]= (1- gamma) * tau_x;
02663 tau_yl[1]= (1- gamma) * tau_y;
02664 tau_xl[1] = vlimit(tau_xl[1], -1*tq_x_ulimit, -1*tq_x_llimit);
02665 tau_yl[1] = vlimit(tau_yl[1], tq_y_llimit, tq_y_ulimit);
02666
02667 double dleg_x[2];
02668 double dleg_y[2];
02669 double tau_y_total = (m_wrenches[1].data[4] + m_wrenches[0].data[4]) / 2;
02670 double dpz;
02671 if (DEBUGP2) {
02672 std::cerr << "tq limit " << tq_x_ulimit << " " << tq_x_llimit << " " << tq_y_ulimit << " " << tq_y_llimit << std::endl;
02673 }
02674 for (size_t i = 0; i < 2; i++) {
02675
02676
02677
02678 dleg_x[i] = m_tau_x[i].update(0,0);
02679 dleg_y[i] = m_tau_y[i].update(tau_y_total, tau_yl[i]);
02680 if (DEBUGP2) {
02681 std::cerr << i << " dleg_x " << dleg_x[i] << std::endl;
02682 std::cerr << i << " dleg_y " << dleg_y[i] << std::endl;
02683 std::cerr << i << " t_x " << m_wrenches[i].data[3] << " "<< tau_xl[i] << std::endl;
02684 std::cerr << i << " t_y " << m_wrenches[i].data[4] << " "<< tau_yl[i] << std::endl;
02685 }
02686 }
02687
02688
02689 hrp::Matrix33 target_R[2];
02690 hrp::Vector3 target_p[2];
02691 for (size_t i = 0; i < 2; i++) {
02692
02693 rats::rotm3times(target_R[i], hrp::rotFromRpy(0, dleg_y[i], 0), target_foot_R[i]);
02694
02695
02696 target_p[i] = target_foot_p[i];
02697 }
02698
02699 double refdfz = 0;
02700 dpz = m_f_z.update((m_wrenches[0].data[2] - m_wrenches[1].data[2]), refdfz);
02701
02702
02703 target_p[0](2) = target_foot_p[0](2);
02704 target_p[1](2) = target_foot_p[1](2);
02705
02706
02707 for (size_t i = 0; i < 2; i++) {
02708 hrp::Link* target = m_robot->link(target_name[i]);
02709 hrp::Vector3 vel_p, vel_r;
02710 vel_p = target_p[i] - target->p;
02711 rats::difference_rotation(vel_r, target->R, target_R[i]);
02712
02713
02714
02715 }
02716
02717
02718 m_robot->joint(m_robot->link("L_ANKLE_P")->jointId)->q = transition_smooth_gain * dleg_y[0] + orgjq;
02719 m_robot->joint(m_robot->link("R_ANKLE_P")->jointId)->q = transition_smooth_gain * dleg_y[1] + orgjq;
02720 } else {
02721
02722 for (int i = 0; i < 2; i++) {
02723 m_tau_x[i].reset();
02724 m_tau_y[i].reset();
02725 m_f_z.reset();
02726 }
02727 }
02728 }
02729 }
02730
02731 void Stabilizer::calcContactMatrix (hrp::dmatrix& tm, const std::vector<hrp::Vector3>& contact_p)
02732 {
02733
02734
02735
02736
02737
02738
02739
02740
02741
02742 }
02743
02744 void Stabilizer::calcTorque ()
02745 {
02746 m_robot->calcForwardKinematics();
02747
02748 hrp::Vector3 root_w_x_v;
02749 hrp::Vector3 g(0, 0, 9.80665);
02750 root_w_x_v = m_robot->rootLink()->w.cross(m_robot->rootLink()->vo + m_robot->rootLink()->w.cross(m_robot->rootLink()->p));
02751 m_robot->rootLink()->dvo = g - root_w_x_v;
02752 m_robot->rootLink()->dw.setZero();
02753
02754 hrp::Vector3 root_f;
02755 hrp::Vector3 root_t;
02756 m_robot->calcInverseDynamics(m_robot->rootLink(), root_f, root_t);
02757
02758
02759
02760
02761
02762
02763
02764
02765
02766
02767
02768
02769
02770
02771
02772
02773
02774
02775
02776
02777
02778 hrp::dmatrix contact_mat, contact_mat_inv;
02779 std::vector<hrp::Vector3> contact_p;
02780 for (size_t j = 0; j < 2; j++) contact_p.push_back(m_robot->sensor<hrp::ForceSensor>(stikp[j].sensor_name)->link->p);
02781 calcContactMatrix(contact_mat, contact_p);
02782 hrp::calcSRInverse(contact_mat, contact_mat_inv, 0.0);
02783 hrp::dvector root_ft(6);
02784 for (size_t j = 0; j < 3; j++) root_ft(j) = root_f(j);
02785 for (size_t j = 0; j < 3; j++) root_ft(j+3) = root_t(j);
02786 hrp::dvector contact_ft(2*6);
02787 contact_ft = contact_mat_inv * root_ft;
02788
02789
02790
02791
02792
02793
02794 for (size_t j = 0; j < 2; j++) {
02795 hrp::JointPathEx jm = hrp::JointPathEx(m_robot, m_robot->rootLink(), m_robot->sensor<hrp::ForceSensor>(stikp[j].sensor_name)->link, dt);
02796 hrp::dmatrix JJ;
02797 jm.calcJacobian(JJ);
02798 hrp::dvector ft(6);
02799 for (size_t i = 0; i < 6; i++) ft(i) = contact_ft(i+j*6);
02800 hrp::dvector tq_from_extft(jm.numJoints());
02801 tq_from_extft = JJ.transpose() * ft;
02802
02803
02804
02805
02806
02807 for (size_t i = 0; i < jm.numJoints(); i++) jm.joint(i)->u -= tq_from_extft(i);
02808 }
02809
02810
02811
02812
02813
02814
02815
02816
02817
02818
02819
02820
02821
02822
02823
02824
02825
02826 };
02827
02828 extern "C"
02829 {
02830
02831 void StabilizerInit(RTC::Manager* manager)
02832 {
02833 RTC::Properties profile(stabilizer_spec);
02834 manager->registerFactory(profile,
02835 RTC::Create<Stabilizer>,
02836 RTC::Delete<Stabilizer>);
02837 }
02838
02839 };
02840
02841