12 #include <hrpModel/Sensor.h> 13 #include <hrpModel/ModelLoaderUtil.h> 15 #include "hrpsys/util/VectorConvert.h" 17 #include <boost/lambda/lambda.hpp> 22 #define deg2rad(x) ((x) * M_PI / 180.0) 25 #define rad2deg(rad) (rad * 180 / M_PI) 32 "implementation_id",
"Stabilizer",
33 "type_name",
"Stabilizer",
34 "description",
"stabilizer",
35 "version", HRPSYS_PACKAGE_VERSION,
37 "category",
"example",
38 "activity_type",
"DataFlowComponent",
41 "lang_type",
"compile",
43 "conf.default.debugLevel",
"0",
48 static std::ostream&
operator<<(std::ostream& os,
const struct RTC::Time &tm)
50 int pre = os.precision();
51 os.setf(std::ios::fixed);
52 os << std::setprecision(6)
53 << (tm.sec + tm.nsec/1e9)
54 << std::setprecision(pre);
55 os.unsetf(std::ios::fixed);
62 :
RTC::DataFlowComponentBase(manager),
64 m_qCurrentIn(
"qCurrent", m_qCurrent),
65 m_qRefIn(
"qRef", m_qRef),
66 m_rpyIn(
"rpy", m_rpy),
67 m_zmpRefIn(
"zmpRef", m_zmpRef),
68 m_StabilizerServicePort(
"StabilizerService"),
69 m_basePosIn(
"basePosIn", m_basePos),
70 m_baseRpyIn(
"baseRpyIn", m_baseRpy),
71 m_contactStatesIn(
"contactStates", m_contactStates),
72 m_toeheelRatioIn(
"toeheelRatio", m_toeheelRatio),
73 m_controlSwingSupportTimeIn(
"controlSwingSupportTime", m_controlSwingSupportTime),
74 m_qRefSeqIn(
"qRefSeq", m_qRefSeq),
75 m_walkingStatesIn(
"walkingStates", m_walkingStates),
76 m_sbpCogOffsetIn(
"sbpCogOffset", m_sbpCogOffset),
77 m_qRefOut(
"q", m_qRef),
78 m_tauOut(
"tau", m_tau),
79 m_zmpOut(
"zmp", m_zmp),
80 m_refCPOut(
"refCapturePoint", m_refCP),
81 m_actCPOut(
"actCapturePoint", m_actCP),
82 m_diffCPOut(
"diffCapturePoint", m_diffCP),
83 m_diffFootOriginExtMomentOut(
"diffFootOriginExtMoment", m_diffFootOriginExtMoment),
84 m_actContactStatesOut(
"actContactStates", m_actContactStates),
85 m_COPInfoOut(
"COPInfo", m_COPInfo),
86 m_emergencySignalOut(
"emergencySignal", m_emergencySignal),
88 m_originRefZmpOut(
"originRefZmp", m_originRefZmp),
89 m_originRefCogOut(
"originRefCog", m_originRefCog),
90 m_originRefCogVelOut(
"originRefCogVel", m_originRefCogVel),
91 m_originNewZmpOut(
"originNewZmp", m_originNewZmp),
92 m_originActZmpOut(
"originActZmp", m_originActZmp),
93 m_originActCogOut(
"originActCog", m_originActCog),
94 m_originActCogVelOut(
"originActCogVel", m_originActCogVel),
95 m_actBaseRpyOut(
"actBaseRpy", m_actBaseRpy),
96 m_currentBasePosOut(
"currentBasePos", m_currentBasePos),
97 m_currentBaseRpyOut(
"currentBaseRpy", m_currentBaseRpy),
98 m_allRefWrenchOut(
"allRefWrench", m_allRefWrench),
99 m_allEECompOut(
"allEEComp", m_allEEComp),
100 m_debugDataOut(
"debugData", m_debugData),
101 control_mode(MODE_IDLE),
102 st_algorithm(
OpenHRP::StabilizerService::TPCC),
103 emergency_check_mode(
OpenHRP::StabilizerService::NO_CHECK),
117 std::cerr <<
"[" <<
m_profile.instance_name <<
"] onInitialize()" << std::endl;
180 std::string nameServer = rtcManager.
getConfig()[
"corba.nameservers"];
181 int comPos = nameServer.find(
",");
183 comPos = nameServer.length();
185 nameServer = nameServer.substr(0, comPos);
191 CosNaming::NamingContext::_duplicate(
naming.getRootContext())
193 std::cerr <<
"[" <<
m_profile.instance_name <<
"]failed to load model[" << prop[
"model"] <<
"]" << std::endl;
194 return RTC::RTC_ERROR;
198 std::vector<std::string> force_sensor_names;
202 for (
unsigned int i=0;
i<npforce; ++
i) {
208 int nvforce =
m_vfs.size();
209 for (
unsigned int i=0;
i<nvforce; ++
i) {
210 for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it =
m_vfs.begin(); it !=
m_vfs.end(); it++ ) {
211 if (it->second.id ==
i) {
212 force_sensor_names.push_back(it->first);
217 int nforce = npforce + nvforce;
224 std::cerr <<
"[" <<
m_profile.instance_name <<
"] force sensor ports (" << npforce <<
")" << std::endl;
225 for (
unsigned int i=0;
i<nforce; ++
i) {
226 std::string force_sensor_name = force_sensor_names[
i];
234 registerInPort(std::string(force_sensor_name+
"Ref").c_str(), *m_ref_wrenchesIn[
i]);
235 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << force_sensor_name << std::endl;
237 std::cerr <<
"[" <<
m_profile.instance_name <<
"] limbCOPOffset ports (" << npforce <<
")" << std::endl;
238 for (
unsigned int i=0;
i<nforce; ++
i) {
239 std::string force_sensor_name = force_sensor_names[
i];
240 std::string nm(
"limbCOPOffset_"+force_sensor_name);
243 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << nm << std::endl;
249 if (end_effectors_str.size() > 0) {
250 size_t prop_num = 10;
251 size_t num = end_effectors_str.size()/prop_num;
252 for (
size_t i = 0;
i < num;
i++) {
253 std::string ee_name, ee_target, ee_base;
258 for (
size_t j = 0;
j < 3;
j++) {
262 for (
int j = 0;
j < 4;
j++ ) {
265 ikp.
localR = Eigen::AngleAxis<double>(tmpv[3],
hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix();
269 bool is_ee_exists =
false;
270 for (
size_t j = 0;
j < npforce;
j++) {
273 while (alink != NULL && alink->
name != ee_base && !is_ee_exists) {
295 stikp.push_back(ikp);
298 if (ee_name.find(
"leg") != std::string::npos &&
jpe_v.back()->numJoints() == 7) {
299 std::vector<double> optw;
300 for (
int j = 0;
j <
jpe_v.back()->numJoints();
j++ ) {
301 if (
j ==
jpe_v.back()->numJoints()-1 ) optw.push_back(0.0);
302 else optw.push_back(1.0);
304 jpe_v.back()->setOptionalWeightVector(optw);
308 act_ee_p.push_back(hrp::Vector3::Zero());
309 act_ee_R.push_back(hrp::Matrix33::Identity());
311 act_force.push_back(hrp::Vector3::Zero());
312 ref_force.push_back(hrp::Vector3::Zero());
315 is_ik_enable.push_back( (ee_name.find(
"leg") != std::string::npos ?
true :
false) );
317 is_zmp_calc_enable.push_back( (ee_name.find(
"leg") != std::string::npos ?
true :
false) );
318 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << ee_name <<
"]" << std::endl;
319 std::cerr <<
"[" <<
m_profile.instance_name <<
"] target = " << m_robot->link(ikp.
target_name)->name <<
", base = " << ee_base <<
", sensor_name = " << ikp.
sensor_name << std::endl;
320 std::cerr <<
"[" <<
m_profile.instance_name <<
"] offset_pos = " << ikp.
localp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
328 std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
330 if (interlocking_joints.size() > 0) {
331 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
332 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Interlocking Joints for [" <<
stikp[
i].ee_name <<
"]" << std::endl;
333 jpe_v[
i]->setInterlockingJointPairIndices(interlocking_joints, std::string(
m_profile.instance_name));
339 act_zmp = hrp::Vector3::Zero();
340 for (
int i = 0;
i < 2;
i++) {
347 double k_ratio = 0.9;
348 for (
int i = 0;
i < 2;
i++) {
355 for (
size_t i = 0;
i <
stikp.size();
i++) {
369 if (ikp.
ee_name.find(
"leg") == std::string::npos) {
372 for (
size_t j = 0;
j < 3;
j++) {
419 double ke = 0, tc = 0;
420 for (
int i = 0;
i < 2;
i++) {
430 pdr = hrp::Vector3::Zero();
434 for (
size_t i = 0;
i <
stikp.size();
i++) {
435 if (
stikp[
i].ee_name.find(
"leg") == std::string::npos)
continue;
443 m_qRef.data.length(m_robot->numJoints());
444 m_tau.data.length(m_robot->numJoints());
446 qorg.resize(m_robot->numJoints());
447 qrefv.resize(m_robot->numJoints());
487 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
488 for (
size_t i = 0;
i <
stikp.size();
i++) {
489 support_polygon_vec.push_back(std::vector<Eigen::Vector2d>(1,Eigen::Vector2d::Zero()));
499 std::cerr <<
"[" <<
m_profile.instance_name <<
"] WARNING! This robot model has no GyroSensor named 'gyrometer'! " << std::endl;
530 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onActivated(" << ec_id <<
")" << std::endl;
537 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onDeactivated(" << ec_id <<
")" << std::endl;
546 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 ) 547 #define DEBUGP2 (loop%10==0) 655 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
714 for (
size_t i = 0;
i <
stikp.size();
i++) {
715 for (
size_t j = 0;
j < 3;
j++) {
763 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
773 for (
size_t i = 0;
i <
stikp.size();
i++) {
774 if (
stikp[
i].ee_name.find(
"leg") == std::string::npos)
continue;
781 leg_c[
i].
rot(0,0) = xv1(0); leg_c[
i].
rot(1,0) = xv1(1); leg_c[
i].
rot(2,0) = xv1(2);
782 leg_c[
i].
rot(0,1) = yv1(0); leg_c[
i].
rot(1,1) = yv1(1); leg_c[
i].
rot(2,1) = yv1(2);
783 leg_c[
i].
rot(0,2) = ez(0); leg_c[
i].
rot(1,2) = ez(1); leg_c[
i].
rot(2,2) = ez(2);
788 foot_origin_pos = tmpc.
pos;
789 foot_origin_rot = tmpc.
rot;
791 foot_origin_pos = leg_c[contact_states_index_map[
"rleg"]].
pos;
792 foot_origin_rot = leg_c[contact_states_index_map[
"rleg"]].
rot;
794 foot_origin_pos = leg_c[contact_states_index_map[
"lleg"]].
pos;
795 foot_origin_rot = leg_c[contact_states_index_map[
"lleg"]].
rot;
806 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
810 m_robot->rootLink()->p = hrp::Vector3::Zero();
811 m_robot->calcForwardKinematics();
816 m_robot->rootLink()->R = act_Rs * (senR.transpose() *
m_robot->rootLink()->R);
817 m_robot->calcForwardKinematics();
821 for (
int i = 0;
i <
m_robot->numJoints();
i++ ) {
826 m_robot->calcForwardKinematics();
838 for (
size_t i = 0;
i <
stikp.size();
i++) {
839 std::string limb_name =
stikp[
i].ee_name;
850 act_zmp = foot_origin_rot.transpose() * (
act_zmp - foot_origin_pos);
851 act_cog = foot_origin_rot.transpose() * (
act_cog - foot_origin_pos);
861 for (
size_t i = 0;
i <
stikp.size();
i++) {
865 act_ee_p[
i] = foot_origin_rot.transpose() * (_act_ee_p - foot_origin_pos);
881 new_refzmp = foot_origin_rot * new_refzmp + foot_origin_pos;
882 for (
size_t i = 0;
i < 2;
i++) {
887 std::cerr <<
"[" <<
m_profile.instance_name <<
"] state values" << std::endl;
888 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 889 <<
"ref_cog = " <<
hrp::Vector3(
ref_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]"))
890 <<
", act_cog = " <<
hrp::Vector3(
act_cog*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[mm]" << std::endl;
891 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 892 <<
"ref_cogvel = " <<
hrp::Vector3(
ref_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]"))
893 <<
", act_cogvel = " <<
hrp::Vector3(
act_cogvel*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[mm/s]" << std::endl;
894 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 895 <<
"ref_zmp = " <<
hrp::Vector3(
ref_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]"))
896 <<
", act_zmp = " <<
hrp::Vector3(
act_zmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[mm]" << std::endl;
898 tmpnew_refzmp = foot_origin_rot.transpose()*(new_refzmp-foot_origin_pos);
899 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 900 <<
"new_zmp = " <<
hrp::Vector3(tmpnew_refzmp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]"))
901 <<
", dif_zmp = " <<
hrp::Vector3((tmpnew_refzmp-
ref_zmp)*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[mm]" << std::endl;
904 std::vector<std::string> ee_name;
906 std::vector<hrp::Vector3> tmp_ref_force, tmp_ref_moment;
907 std::vector<double> limb_gains;
908 std::vector<hrp::dvector6> ee_forcemoment_distribution_weight;
909 std::vector<double> tmp_toeheel_ratio;
911 std::vector<hrp::Vector3> ee_pos, cop_pos;
912 std::vector<hrp::Matrix33> ee_rot;
913 std::vector<bool> is_contact_list;
914 is_contact_list.reserve(
stikp.size());
915 for (
size_t i = 0;
i <
stikp.size();
i++) {
919 ee_pos.push_back(target->
p + target->
R * ikp.
localp);
921 ee_rot.push_back(target->
R * ikp.
localR);
922 ee_name.push_back(ikp.
ee_name);
926 rel_ee_pos.push_back(foot_origin_rot.transpose() * (ee_pos.back() - foot_origin_pos));
927 rel_ee_rot.push_back(foot_origin_rot.transpose() * ee_rot.back());
931 ee_forcemoment_distribution_weight.push_back(hrp::dvector6::Zero(6,1));
932 for (
size_t j = 0;
j < 6;
j++) {
940 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ee values" << std::endl;
942 for (
size_t i = 0;
i < ee_name.size();
i++) {
943 tmpp = foot_origin_rot.transpose()*(ee_pos[
i]-foot_origin_pos);
944 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 945 <<
"ee_pos (" << ee_name[
i] <<
") = " <<
hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]"));
946 tmpp = foot_origin_rot.transpose()*(cop_pos[
i]-foot_origin_pos);
947 std::cerr <<
", cop_pos (" << ee_name[
i] <<
") = " <<
hrp::Vector3(tmpp*1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[mm]" << std::endl;
953 Eigen::Vector2d tmp_new_refzmp(new_refzmp.head(2));
963 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
967 }
else if (
st_algorithm == OpenHRP::StabilizerService::EEFMQP) {
969 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
973 (
st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP));
974 }
else if (
st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP) {
976 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
980 (
st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP), is_contact_list);
981 }
else if (
st_algorithm == OpenHRP::StabilizerService::EEFMQPCOP2) {
983 ee_pos, cop_pos, ee_rot, ee_name, limb_gains, tmp_toeheel_ratio,
986 ee_forcemoment_distribution_weight,
991 new_refzmp = foot_origin_rot.transpose() * (new_refzmp - foot_origin_pos);
997 std::vector<bool> large_swing_f_diff(3,
false);
1000 for (
size_t i = 0;
i <
stikp.size();
i++) {
1002 std::vector<bool> large_swing_m_diff(3,
false);
1020 sensor_force = ee_R.transpose() * sensor_force;
1021 ee_moment = ee_R.transpose() * ee_moment;
1022 if ( i == 0 ) f_diff += -1*sensor_force;
1023 else f_diff += sensor_force;
1024 for (
size_t j = 0;
j < 3; ++
j) {
1035 for (
size_t j = 0;
j < 3; ++
j) {
1050 sensor_force = foot_origin_rot.transpose() * ee_R * sensor_force;
1051 ee_moment = foot_origin_rot.transpose() * ee_R * ee_moment;
1061 projected_normal.at(i) = plane_x.dot(normal_vector) * plane_x + plane_y.dot(normal_vector) * plane_y;
1077 for (
size_t i = 0;
i < 3; ++
i) {
1082 tmp_damping_gain,
stikp[0].eefm_pos_time_const_support);
1089 tmp_damping_gain,
stikp[0].eefm_pos_time_const_support);
1091 double remain_swing_time;
1113 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Control values" << std::endl;
1115 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 1118 for (
size_t i = 0;
i < ee_name.size();
i++) {
1119 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 1120 <<
"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], " 1121 <<
"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;
1134 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
1140 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
1142 for (
int j = 0;
j <
jpe_v[i]->numJoints();
j++ ){
1143 int idx =
jpe_v[i]->joint(
j)->jointId;
1151 m_robot->calcForwardKinematics();
1169 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
1173 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
1181 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
m_qRef.tm <<
"] Move to MODE_IDLE" << std::endl;
1186 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
1193 m_robot->calcForwardKinematics();
1198 if (
st_algorithm != OpenHRP::StabilizerService::TPCC) {
1208 for (
size_t i = 0;
i <
stikp.size();
i++) {
1216 #ifdef FORCE_MOMENT_DIFF_CONTROL 1233 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Reset prev_ref_cog for transition (MODE_IDLE=>MODE_ST)." << std::endl;
1236 if (
st_algorithm != OpenHRP::StabilizerService::TPCC) {
1243 ref_zmp = foot_origin_rot.transpose() * (
ref_zmp - foot_origin_pos);
1244 ref_cog = foot_origin_rot.transpose() * (
ref_cog - foot_origin_pos);
1252 for (
size_t i = 0;
i <
stikp.size();
i++) {
1253 stikp[
i].target_ee_diff_p = foot_origin_rot.transpose() * (
target_ee_p[
i] - foot_origin_pos);
1280 double tmpfz = 0, tmpfz2 = 0.0;
1281 for (
size_t i = 0;
i <
stikp.size();
i++) {
1289 tmpzmpx += nf(2) * fsp(0) - (fsp(2) - zmp_z) * nf(0) - nm(1);
1290 tmpzmpy += nf(2) * fsp(1) - (fsp(2) - zmp_z) * nf(1) + nm(0);
1295 hrp::Vector3 ee_fsp = eeR.transpose() * (fsp - (target->
p + target->
R *
stikp[i].localp));
1296 nf = eeR.transpose() * nf;
1297 nm = eeR.transpose() * nm;
1299 double tmpcopmy = nf(2) * ee_fsp(0) - nf(0) * ee_fsp(2) - nm(1);
1300 double tmpcopmx = nf(2) * ee_fsp(1) - nf(1) * ee_fsp(2) + nm(0);
1301 double tmpcopfz = nf(2);
1312 ret_zmp =
hrp::Vector3(tmpzmpx / tmpfz, tmpzmpy / tmpfz, zmp_z);
1320 bool is_cop_outside =
false;
1322 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Check Emergency State (seq = " << (
is_seq_interpolating?
"interpolating":
"empty") <<
")" << std::endl;
1326 std::cerr <<
"[" <<
m_profile.instance_name <<
"] COP check" << std::endl;
1328 for (
size_t i = 0;
i <
stikp.size();
i++) {
1329 if (
stikp[
i].ee_name.find(
"leg") == std::string::npos)
continue;
1333 is_cop_outside = is_cop_outside ||
1338 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
i].ee_name <<
"] " 1344 is_cop_outside =
true;
1348 is_cop_outside =
false;
1351 bool is_cp_outside =
false;
1353 Eigen::Vector2d tmp_cp =
act_cp.head(2);
1358 std::cerr <<
"[" <<
m_profile.instance_name <<
"] CP value " <<
"[" <<
act_cp(0) <<
"," <<
act_cp(1) <<
"] [m], " 1360 << (is_cp_outside?
"Outside":
"Inside")
1363 if (is_cp_outside) {
1366 <<
"] CP too large error " <<
"[" <<
act_cp(0) <<
"," <<
act_cp(1) <<
"] [m]" << std::endl;
1375 bool is_falling =
false, will_fall =
false;
1377 double total_force = 0.0;
1378 for (
size_t i = 0;
i <
stikp.size();
i++) {
1385 <<
"] " <<
stikp[i].ee_name <<
" cannot support total weight, " 1399 fall_direction = fall_direction / total_force;
1401 fall_direction = hrp::Vector3::Zero();
1403 if (fall_direction.norm() > sin(
tilt_margin[1])) {
1407 <<
"] robot is falling down toward " <<
"(" << fall_direction(0) <<
"," << fall_direction(1) <<
") direction" << std::endl;
1416 case OpenHRP::StabilizerService::NO_CHECK:
1419 case OpenHRP::StabilizerService::COP:
1422 case OpenHRP::StabilizerService::CP:
1425 case OpenHRP::StabilizerService::TILT:
1432 std::cerr <<
"[" <<
m_profile.instance_name <<
"] EmergencyCheck (" 1434 <<
") " << (
is_emergency?
"emergency":
"non-emergency") << std::endl;
1446 bool is_root_rot_limit =
false;
1447 for (
size_t i = 0;
i < 2;
i++) {
1455 m_robot->calcForwardKinematics();
1458 if (
DEBUGP || (is_root_rot_limit &&
loop%200==0) ) {
1459 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Root rot control" << std::endl;
1460 if (is_root_rot_limit) std::cerr <<
"[" <<
m_profile.instance_name <<
"] Root rot limit reached!!" << std::endl;
1461 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ref = [" <<
rad2deg(ref_root_rpy(0)) <<
" " <<
rad2deg(ref_root_rpy(1)) <<
"], " 1470 for (
size_t i = 0;
i <
stikp.size();
i++) {
1490 std::cerr <<
"[" <<
m_profile.instance_name <<
"] SwingSupportLimbGain = [";
1491 for (
size_t i = 0;
i <
stikp.size();
i++) std::cerr <<
stikp[
i].swing_support_gain <<
" ";
1492 std::cerr <<
"], ref_contact_states = [";
1494 std::cerr <<
"], sstime = [";
1496 std::cerr <<
"], toeheel_ratio = [";
1498 std::cerr <<
"], support_time = [";
1499 for (
size_t i = 0;
i <
stikp.size();
i++) std::cerr <<
stikp[
i].support_time <<
" ";
1500 std::cerr <<
"]" << std::endl;
1511 for (
size_t i = 0;
i < 2;
i++) {
1514 newcog(
i) = uu *
dt + cog(
i);
1522 for (
size_t i = 0;
i <
stikp.size();
i++) {
1529 size_t max_ik_loop_count = 0;
1530 for (
size_t i = 0;
i <
stikp.size();
i++) {
1531 if (max_ik_loop_count <
stikp[
i].ik_loop_count) max_ik_loop_count =
stikp[
i].ik_loop_count;
1533 for (
size_t jj = 0; jj < max_ik_loop_count; jj++) {
1535 for (
size_t i = 0;
i < 2;
i++) {
1536 m_robot->rootLink()->p(
i) =
m_robot->rootLink()->p(
i) + 0.9 * (newcog(
i) - tmpcm(
i));
1538 m_robot->calcForwardKinematics();
1539 for (
size_t i = 0;
i <
stikp.size();
i++) {
1554 for (
int i = 0;
i <
m_robot->numJoints();
i++ ) {
1557 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
1559 for (
int j = 0;
j <
jpe_v[i]->numJoints();
j++ ){
1560 int idx =
jpe_v[i]->joint(
j)->jointId;
1566 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
1568 if (
jpe_v[i]->numJoints() == 7) {
1569 int idx =
jpe_v[i]->joint(
jpe_v[i]->numJoints() -1)->jointId;
1583 m_robot->calcForwardKinematics();
1587 m_robot->rootLink()->R = act_Rs * (senR.transpose() *
m_robot->rootLink()->R);
1588 m_robot->calcForwardKinematics();
1594 for (
size_t i = 0;
i <
stikp.size();
i++) {
1596 stikp[
i].target_ee_diff_p -= foot_origin_rot.transpose() * (target->
p + target->
R *
stikp[
i].localp - foot_origin_pos);
1597 stikp[
i].target_ee_diff_r = (foot_origin_rot.transpose() * target->
R *
stikp[
i].localR).transpose() *
stikp[
i].target_ee_diff_r;
1611 std::vector<hrp::Vector3> current_d_foot_pos;
1612 for (
size_t i = 0;
i <
stikp.size();
i++)
1613 current_d_foot_pos.push_back(foot_origin_rot *
stikp[
i].d_foot_pos);
1620 std::vector<hrp::Vector3> tmpp(
stikp.size());
1621 std::vector<hrp::Matrix33> tmpR(
stikp.size());
1622 double tmp_d_pos_z_root = 0.0;
1623 for (
size_t i = 0; i <
stikp.size(); i++) {
1638 tmpp[i] = tmpp[i] + foot_origin_rot *
stikp[i].d_pos_swing;
1645 for (
size_t i = 0; i <
stikp.size(); i++) {
1647 for (
size_t jj = 0; jj <
stikp[i].ik_loop_count; jj++) {
1663 for (
size_t i = 0;
i <
stikp.size();
i++) {
1665 double limit_pos = 30 * 1e-3;
1666 double limit_rot =
deg2rad(10);
1671 stikp[
i].target_ee_diff_p_filter->reset(
stikp[
i].d_pos_swing);
1672 stikp[
i].target_ee_diff_r_filter->reset(
stikp[
i].d_rpy_swing);
1676 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));
1677 double lvlimit = -50 * 1e-3 *
dt, uvlimit = 50 * 1e-3 *
dt;
1678 hrp::Vector3 limit_by_lvlimit =
stikp[i].prev_d_pos_swing + lvlimit * hrp::Vector3::Ones();
1679 hrp::Vector3 limit_by_uvlimit =
stikp[i].prev_d_pos_swing + uvlimit * hrp::Vector3::Ones();
1680 stikp[i].d_pos_swing =
vlimit(
vlimit(tmpdiffp, -1 * limit_pos, limit_pos), limit_by_lvlimit, limit_by_uvlimit);
1686 hrp::Vector3 limit_by_lvlimit =
stikp[i].prev_d_rpy_swing + lvlimit * hrp::Vector3::Ones();
1687 hrp::Vector3 limit_by_uvlimit =
stikp[i].prev_d_rpy_swing + uvlimit * hrp::Vector3::Ones();
1688 stikp[i].d_rpy_swing =
vlimit(
vlimit(tmpdiffr, -1 * limit_rot, limit_rot), limit_by_lvlimit, limit_by_uvlimit);
1695 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Swing foot control" << std::endl;
1696 for (
size_t i = 0;
i <
stikp.size();
i++) {
1697 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 1698 <<
"d_rpy_swing (" <<
stikp[
i].ee_name <<
") = " << (
stikp[
i].d_rpy_swing /
M_PI * 180.0).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[deg], " 1699 <<
"d_pos_swing (" <<
stikp[
i].ee_name <<
") = " << (
stikp[
i].d_pos_swing * 1e3).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[mm]" << std::endl;
1706 double tmp_d_pos_z_root = 0.0, prev_d_pos_z_root =
d_pos_z_root;
1708 for (
size_t i = 0;
i <
stikp.size();
i++) {
1713 double limb_length_limitation =
stikp[i].max_limb_length -
stikp[i].limb_length_margin;
1714 double tmp = limb_length_limitation * limb_length_limitation - targetp(0) * targetp(0) - targetp(1) * targetp(1);
1715 if (targetp.norm() > limb_length_limitation && tmp >= 0) {
1716 tmp_d_pos_z_root =
std::min(tmp_d_pos_z_root, targetp(2) + std::sqrt(tmp));
1732 const double DD,
const double TT)
1734 return (1/DD * (tau_d - tau) - 1/TT * prev_d) *
dt + prev_d;
1740 return (- prev_d.cwiseQuotient(TT)) *
dt + prev_d;
1746 return - 1/TT * prev_d *
dt + prev_d;
1752 return ((tau_d - tau).cwiseQuotient(DD) - prev_d.cwiseQuotient(TT)) *
dt + prev_d;
1768 if ( !
on_ground ) act_ext_moment = ref_ext_moment;
1772 std::cerr <<
"[" <<
m_profile.instance_name <<
"] DiffStaticBalancePointOffset" << std::endl;
1773 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 1774 <<
"ref_ext_moment = " << ref_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[mm], " 1775 <<
"act_ext_moment = " << act_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[mm], " 1776 <<
"diff ext_moment = " <<
diff_foot_origin_ext_moment.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[mm]" << std::endl;
1818 <<
"] Sync IDLE => ST" << std::endl;
1822 pdr = hrp::Vector3::Zero();
1824 for (
size_t i = 0;
i <
stikp.size();
i++) {
1846 <<
"] Sync ST => IDLE" << std::endl;
1848 for (
int i = 0;
i <
m_robot->numJoints();
i++ ) {
1859 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " <<
"Start ST" << std::endl;
1864 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " <<
"Start ST DONE" << std::endl;
1873 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " <<
"Stop ST" << std::endl;
1878 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " <<
"Stop ST DONE" << std::endl;
1883 std::cerr <<
"[" <<
m_profile.instance_name <<
"] getParameter" << std::endl;
1884 for (
size_t i = 0;
i < 2;
i++) {
1899 for (
size_t i = 0;
i < 2;
i++) {
1907 i_stp.ref_capture_point[
i] =
ref_cp(
i);
1908 i_stp.act_capture_point[
i] =
act_cp(
i);
1911 i_stp.eefm_pos_time_const_support.length(
stikp.size());
1912 i_stp.eefm_pos_damping_gain.length(
stikp.size());
1913 i_stp.eefm_pos_compensation_limit.length(
stikp.size());
1914 i_stp.eefm_swing_pos_spring_gain.length(
stikp.size());
1915 i_stp.eefm_swing_pos_time_const.length(
stikp.size());
1916 i_stp.eefm_rot_time_const.length(
stikp.size());
1917 i_stp.eefm_rot_damping_gain.length(
stikp.size());
1918 i_stp.eefm_rot_compensation_limit.length(
stikp.size());
1919 i_stp.eefm_swing_rot_spring_gain.length(
stikp.size());
1920 i_stp.eefm_swing_rot_time_const.length(
stikp.size());
1921 i_stp.eefm_ee_moment_limit.length(
stikp.size());
1922 i_stp.eefm_ee_forcemoment_distribution_weight.length(
stikp.size());
1923 for (
size_t j = 0;
j <
stikp.size();
j++) {
1924 i_stp.eefm_pos_damping_gain[
j].length(3);
1925 i_stp.eefm_pos_time_const_support[
j].length(3);
1926 i_stp.eefm_swing_pos_spring_gain[
j].length(3);
1927 i_stp.eefm_swing_pos_time_const[
j].length(3);
1928 i_stp.eefm_rot_damping_gain[
j].length(3);
1929 i_stp.eefm_rot_time_const[
j].length(3);
1930 i_stp.eefm_swing_rot_spring_gain[
j].length(3);
1931 i_stp.eefm_swing_rot_time_const[
j].length(3);
1932 i_stp.eefm_ee_moment_limit[
j].length(3);
1933 i_stp.eefm_ee_forcemoment_distribution_weight[
j].length(6);
1934 for (
size_t i = 0;
i < 3;
i++) {
1935 i_stp.eefm_pos_damping_gain[
j][
i] =
stikp[
j].eefm_pos_damping_gain(
i);
1936 i_stp.eefm_pos_time_const_support[
j][
i] =
stikp[
j].eefm_pos_time_const_support(
i);
1937 i_stp.eefm_swing_pos_spring_gain[
j][
i] =
stikp[
j].eefm_swing_pos_spring_gain(
i);
1938 i_stp.eefm_swing_pos_time_const[
j][
i] =
stikp[
j].eefm_swing_pos_time_const(
i);
1939 i_stp.eefm_rot_damping_gain[
j][
i] =
stikp[
j].eefm_rot_damping_gain(
i);
1940 i_stp.eefm_rot_time_const[
j][
i] =
stikp[
j].eefm_rot_time_const(
i);
1941 i_stp.eefm_swing_rot_spring_gain[
j][
i] =
stikp[
j].eefm_swing_rot_spring_gain(
i);
1942 i_stp.eefm_swing_rot_time_const[
j][
i] =
stikp[
j].eefm_swing_rot_time_const(
i);
1943 i_stp.eefm_ee_moment_limit[
j][
i] =
stikp[
j].eefm_ee_moment_limit(
i);
1944 i_stp.eefm_ee_forcemoment_distribution_weight[
j][
i] =
stikp[
j].eefm_ee_forcemoment_distribution_weight(
i);
1945 i_stp.eefm_ee_forcemoment_distribution_weight[
j][
i+3] =
stikp[
j].eefm_ee_forcemoment_distribution_weight(
i+3);
1947 i_stp.eefm_pos_compensation_limit[
j] =
stikp[
j].eefm_pos_compensation_limit;
1948 i_stp.eefm_rot_compensation_limit[
j] =
stikp[
j].eefm_rot_compensation_limit;
1950 for (
size_t i = 0;
i < 3;
i++) {
1962 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
1964 i_stp.eefm_support_polygon_vertices_sequence.length(support_polygon_vec.size());
1965 for (
size_t ee_idx = 0; ee_idx < support_polygon_vec.size(); ee_idx++) {
1966 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices.length(support_polygon_vec[ee_idx].
size());
1967 for (
size_t v_idx = 0; v_idx < support_polygon_vec[ee_idx].size(); v_idx++) {
1968 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[0] = support_polygon_vec[ee_idx][v_idx](0);
1969 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[1] = support_polygon_vec[ee_idx][v_idx](1);
1977 i_stp.eefm_ee_error_cutoff_freq =
stikp[0].target_ee_diff_p_filter->getCutOffFreq();
1980 for (
size_t i = 0;
i < 3; ++
i) {
1997 i_stp.foot_origin_offset.length(2);
1998 for (
size_t i = 0;
i < i_stp.foot_origin_offset.length();
i++) {
1999 i_stp.foot_origin_offset[
i].length(3);
2016 case MODE_IDLE: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_IDLE;
break;
2017 case MODE_AIR: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_AIR;
break;
2018 case MODE_ST: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_ST;
break;
2019 case MODE_SYNC_TO_IDLE: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_SYNC_TO_IDLE;
break;
2020 case MODE_SYNC_TO_AIR: i_stp.controller_mode = OpenHRP::StabilizerService::MODE_SYNC_TO_AIR;
break;
2024 i_stp.end_effector_list.length(
stikp.size());
2028 i_stp.limb_length_margin.length(
stikp.size());
2030 for (
size_t i = 0;
i < 2;
i++) {
2034 for (
size_t i = 0;
i <
stikp.size();
i++) {
2036 OpenHRP::AutoBalancerService::Footstep ret_ee;
2038 memcpy(ret_ee.pos, cur_ee.
pos.data(),
sizeof(double)*3);
2040 Eigen::Quaternion<double> qt(cur_ee.
rot);
2041 ret_ee.rot[0] = qt.w();
2042 ret_ee.rot[1] = qt.x();
2043 ret_ee.rot[2] = qt.y();
2044 ret_ee.rot[3] = qt.z();
2046 ret_ee.leg =
stikp.at(
i).ee_name.c_str();
2048 i_stp.end_effector_list[
i] = ret_ee;
2049 i_stp.limb_length_margin[
i] =
stikp[
i].limb_length_margin;
2051 i_stp.ik_limb_parameters.length(
jpe_v.size());
2052 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2053 OpenHRP::StabilizerService::IKLimbParameters& ilp = i_stp.ik_limb_parameters[
i];
2054 ilp.ik_optional_weight_vector.length(
jpe_v[
i]->numJoints());
2055 std::vector<double> ov;
2056 ov.resize(
jpe_v[
i]->numJoints());
2057 jpe_v[
i]->getOptionalWeightVector(ov);
2058 for (
size_t j = 0;
j <
jpe_v[
i]->numJoints();
j++) {
2059 ilp.ik_optional_weight_vector[
j] = ov[
j];
2061 ilp.sr_gain =
jpe_v[
i]->getSRGain();
2062 ilp.avoid_gain =
stikp[
i].avoid_gain;
2063 ilp.reference_gain =
stikp[
i].reference_gain;
2064 ilp.manipulability_limit =
jpe_v[
i]->getManipulabilityLimit();
2065 ilp.ik_loop_count =
stikp[
i].ik_loop_count;
2072 std::cerr <<
"[" <<
m_profile.instance_name <<
"] setParameter" << std::endl;
2073 for (
size_t i = 0;
i < 2;
i++) {
2079 std::cerr <<
"[" <<
m_profile.instance_name <<
"] TPCC" << std::endl;
2097 std::cerr <<
"[" <<
m_profile.instance_name <<
"] EEFM" << std::endl;
2098 for (
size_t i = 0;
i < 2;
i++) {
2106 ref_cp(
i) = i_stp.ref_capture_point[
i];
2107 act_cp(
i) = i_stp.act_capture_point[
i];
2110 bool is_damping_parameter_ok =
true;
2111 if ( i_stp.eefm_pos_damping_gain.length () ==
stikp.size() &&
2112 i_stp.eefm_pos_time_const_support.length () ==
stikp.size() &&
2113 i_stp.eefm_pos_compensation_limit.length () ==
stikp.size() &&
2114 i_stp.eefm_swing_pos_spring_gain.length () ==
stikp.size() &&
2115 i_stp.eefm_swing_pos_time_const.length () ==
stikp.size() &&
2116 i_stp.eefm_rot_damping_gain.length () ==
stikp.size() &&
2117 i_stp.eefm_rot_time_const.length () ==
stikp.size() &&
2118 i_stp.eefm_rot_compensation_limit.length () ==
stikp.size() &&
2119 i_stp.eefm_swing_rot_spring_gain.length () ==
stikp.size() &&
2120 i_stp.eefm_swing_rot_time_const.length () ==
stikp.size() &&
2121 i_stp.eefm_ee_moment_limit.length () ==
stikp.size() &&
2122 i_stp.eefm_ee_forcemoment_distribution_weight.length () ==
stikp.size()) {
2123 is_damping_parameter_ok =
true;
2124 for (
size_t j = 0;
j <
stikp.size();
j++) {
2125 for (
size_t i = 0;
i < 3;
i++) {
2126 stikp[
j].eefm_pos_damping_gain(
i) = i_stp.eefm_pos_damping_gain[
j][
i];
2127 stikp[
j].eefm_pos_time_const_support(
i) = i_stp.eefm_pos_time_const_support[
j][
i];
2128 stikp[
j].eefm_swing_pos_spring_gain(
i) = i_stp.eefm_swing_pos_spring_gain[
j][
i];
2129 stikp[
j].eefm_swing_pos_time_const(
i) = i_stp.eefm_swing_pos_time_const[
j][
i];
2130 stikp[
j].eefm_rot_damping_gain(
i) = i_stp.eefm_rot_damping_gain[
j][
i];
2131 stikp[
j].eefm_rot_time_const(
i) = i_stp.eefm_rot_time_const[
j][
i];
2132 stikp[
j].eefm_swing_rot_spring_gain(
i) = i_stp.eefm_swing_rot_spring_gain[
j][
i];
2133 stikp[
j].eefm_swing_rot_time_const(
i) = i_stp.eefm_swing_rot_time_const[
j][
i];
2134 stikp[
j].eefm_ee_moment_limit(
i) = i_stp.eefm_ee_moment_limit[
j][
i];
2135 stikp[
j].eefm_ee_forcemoment_distribution_weight(
i) = i_stp.eefm_ee_forcemoment_distribution_weight[
j][
i];
2136 stikp[
j].eefm_ee_forcemoment_distribution_weight(
i+3) = i_stp.eefm_ee_forcemoment_distribution_weight[
j][
i+3];
2138 stikp[
j].eefm_pos_compensation_limit = i_stp.eefm_pos_compensation_limit[
j];
2139 stikp[
j].eefm_rot_compensation_limit = i_stp.eefm_rot_compensation_limit[
j];
2142 is_damping_parameter_ok =
false;
2144 for (
size_t i = 0;
i < 3;
i++) {
2157 if (i_stp.eefm_support_polygon_vertices_sequence.length() !=
stikp.size()) {
2158 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;
2160 std::cerr <<
"[" <<
m_profile.instance_name <<
"] eefm_support_polygon_vertices_sequence set" << std::endl;
2161 std::vector<std::vector<Eigen::Vector2d> > support_polygon_vec;
2162 for (
size_t ee_idx = 0; ee_idx < i_stp.eefm_support_polygon_vertices_sequence.length(); ee_idx++) {
2163 std::vector<Eigen::Vector2d> tvec;
2164 for (
size_t v_idx = 0; v_idx < i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices.length(); v_idx++) {
2165 tvec.push_back(Eigen::Vector2d(i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[0],
2166 i_stp.eefm_support_polygon_vertices_sequence[ee_idx].vertices[v_idx].pos[1]));
2168 support_polygon_vec.push_back(tvec);
2175 for (
size_t i = 0;
i < 3; ++
i) {
2183 for (
size_t i = 0;
i <
stikp.size();
i++) {
2184 stikp[
i].target_ee_diff_p_filter->setCutOffFreq(i_stp.eefm_ee_error_cutoff_freq);
2185 stikp[
i].target_ee_diff_r_filter->setCutOffFreq(i_stp.eefm_ee_error_cutoff_freq);
2186 stikp[
i].limb_length_margin = i_stp.limb_length_margin[
i];
2207 for (
size_t i = 0;
i < 2;
i++) {
2213 for (
size_t i = 0;
i < i_stp.end_effector_list.length();
i++) {
2214 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)));
2215 memcpy(it->localp.data(), i_stp.end_effector_list[
i].pos,
sizeof(double)*3);
2216 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();
2219 std::cerr <<
"[" <<
m_profile.instance_name <<
"] cannot change end-effectors except during MODE_IDLE" << std::endl;
2221 for (std::vector<STIKParam>::const_iterator it =
stikp.begin(); it !=
stikp.end(); it++) {
2222 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << it->ee_name <<
"]" << std::endl;
2223 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localpos = " << it->localp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
2224 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localR = " << it->localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"",
" [",
"]")) << std::endl;
2226 if (i_stp.foot_origin_offset.length () != 2) {
2227 std::cerr <<
"[" <<
m_profile.instance_name <<
"] foot_origin_offset cannot be set. Length " << i_stp.foot_origin_offset.length() <<
" != " << 2 << std::endl;
2229 std::cerr <<
"[" <<
m_profile.instance_name <<
"] foot_origin_offset cannot be set. Current control_mode is " <<
control_mode << std::endl;
2231 for (
size_t i = 0;
i < i_stp.foot_origin_offset.length();
i++) {
2237 std::cerr <<
"[" <<
m_profile.instance_name <<
"] foot_origin_offset is ";
2238 for (
size_t i = 0;
i < 2;
i++) {
2239 std::cerr <<
foot_origin_offset[
i].format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"));
2241 std::cerr <<
"[m]" << std::endl;
2245 if (is_damping_parameter_ok) {
2246 for (
size_t j = 0;
j <
stikp.size();
j++) {
2247 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
j].ee_name <<
"] eefm_rot_damping_gain = " 2248 <<
stikp[
j].eefm_rot_damping_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
2249 <<
", eefm_rot_time_const = " 2250 <<
stikp[
j].eefm_rot_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
2251 <<
"[s]" << std::endl;
2252 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
j].ee_name <<
"] eefm_pos_damping_gain = " 2253 <<
stikp[
j].eefm_pos_damping_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
2254 <<
", eefm_pos_time_const_support = " 2255 <<
stikp[
j].eefm_pos_time_const_support.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]"))
2256 <<
"[s]" << std::endl;
2257 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
j].ee_name <<
"] " 2258 <<
"eefm_pos_compensation_limit = " <<
stikp[
j].eefm_pos_compensation_limit <<
"[m], " 2259 <<
"eefm_rot_compensation_limit = " <<
stikp[
j].eefm_rot_compensation_limit <<
"[rad], " 2260 <<
"eefm_ee_moment_limit = " <<
stikp[
j].eefm_ee_moment_limit.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[Nm]" << std::endl;
2261 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
j].ee_name <<
"] " 2262 <<
"eefm_swing_pos_spring_gain = " <<
stikp[
j].eefm_swing_pos_spring_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
", " 2263 <<
"eefm_swing_pos_time_const = " <<
stikp[
j].eefm_swing_pos_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
", " 2264 <<
"eefm_swing_rot_spring_gain = " <<
stikp[
j].eefm_swing_rot_spring_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
", " 2265 <<
"eefm_swing_pos_time_const = " <<
stikp[
j].eefm_swing_pos_time_const.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
", " 2267 std::cerr <<
"[" <<
m_profile.instance_name <<
"] [" <<
stikp[
j].ee_name <<
"] " 2268 <<
"eefm_ee_forcemoment_distribution_weight = " <<
stikp[
j].eefm_ee_forcemoment_distribution_weight.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"" << std::endl;
2271 std::cerr <<
"[" <<
m_profile.instance_name <<
"] eefm damping parameters cannot be set because of invalid param." << std::endl;
2274 std::cerr <<
"[" <<
m_profile.instance_name <<
"] cogvel_cutoff_freq = " <<
act_cogvel_filter->getCutOffFreq() <<
"[Hz]" << std::endl;
2277 std::cerr <<
"[" <<
m_profile.instance_name <<
"] eefm_ee_error_cutoff_freq = " <<
stikp[0].target_ee_diff_p_filter->getCutOffFreq() <<
"[Hz]" << std::endl;
2278 std::cerr <<
"[" <<
m_profile.instance_name <<
"] COMMON" << std::endl;
2285 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;
2293 std::cerr <<
"[" <<
m_profile.instance_name <<
"] IK limb parameters" << std::endl;
2294 bool is_ik_limb_parameter_valid_length =
true;
2295 if (i_stp.ik_limb_parameters.length() !=
jpe_v.size()) {
2296 is_ik_limb_parameter_valid_length =
false;
2297 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;
2299 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2300 if (
jpe_v[
i]->numJoints() != i_stp.ik_limb_parameters[
i].ik_optional_weight_vector.length())
2301 is_ik_limb_parameter_valid_length =
false;
2303 if (is_ik_limb_parameter_valid_length) {
2304 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2305 const OpenHRP::StabilizerService::IKLimbParameters& ilp = i_stp.ik_limb_parameters[
i];
2306 std::vector<double> ov;
2307 ov.resize(
jpe_v[
i]->numJoints());
2308 for (
size_t j = 0;
j <
jpe_v[
i]->numJoints();
j++) {
2309 ov[
j] = ilp.ik_optional_weight_vector[
j];
2311 jpe_v[
i]->setOptionalWeightVector(ov);
2312 jpe_v[
i]->setSRGain(ilp.sr_gain);
2313 stikp[
i].avoid_gain = ilp.avoid_gain;
2314 stikp[
i].reference_gain = ilp.reference_gain;
2315 jpe_v[
i]->setManipulabilityLimit(ilp.manipulability_limit);
2316 stikp[
i].ik_loop_count = ilp.ik_loop_count;
2319 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ik_optional_weight_vector invalid length! Cannot be set. (input = [";
2320 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2321 std::cerr << i_stp.ik_limb_parameters[
i].ik_optional_weight_vector.length() <<
", ";
2323 std::cerr <<
"], desired = [";
2324 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2325 std::cerr <<
jpe_v[
i]->numJoints() <<
", ";
2327 std::cerr <<
"])" << std::endl;
2330 if (is_ik_limb_parameter_valid_length) {
2331 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ik_optional_weight_vectors = ";
2332 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2333 std::vector<double> ov;
2334 ov.resize(
jpe_v[
i]->numJoints());
2335 jpe_v[
i]->getOptionalWeightVector(ov);
2337 for (
size_t j = 0;
j <
jpe_v[
i]->numJoints();
j++) {
2338 std::cerr << ov[
j] <<
" ";
2342 std::cerr << std::endl;
2343 std::cerr <<
"[" <<
m_profile.instance_name <<
"] sr_gains = [";
2344 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2345 std::cerr <<
jpe_v[
i]->getSRGain() <<
", ";
2347 std::cerr <<
"]" << std::endl;
2348 std::cerr <<
"[" <<
m_profile.instance_name <<
"] avoid_gains = [";
2349 for (
size_t i = 0;
i <
stikp.size();
i++) {
2350 std::cerr <<
stikp[
i].avoid_gain <<
", ";
2352 std::cerr <<
"]" << std::endl;
2353 std::cerr <<
"[" <<
m_profile.instance_name <<
"] reference_gains = [";
2354 for (
size_t i = 0;
i <
stikp.size();
i++) {
2355 std::cerr <<
stikp[
i].reference_gain <<
", ";
2357 std::cerr <<
"]" << std::endl;
2358 std::cerr <<
"[" <<
m_profile.instance_name <<
"] manipulability_limits = [";
2359 for (
size_t i = 0;
i <
jpe_v.size();
i++) {
2360 std::cerr <<
jpe_v[
i]->getManipulabilityLimit() <<
", ";
2362 std::cerr <<
"]" << std::endl;
2363 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ik_loop_count = [";
2364 for (
size_t i = 0;
i <
stikp.size();
i++) {
2365 std::cerr <<
stikp[
i].ik_loop_count <<
", ";
2367 std::cerr <<
"]" << std::endl;
2373 switch (_st_algorithm) {
2374 case OpenHRP::StabilizerService::TPCC:
2376 case OpenHRP::StabilizerService::EEFM:
2378 case OpenHRP::StabilizerService::EEFMQP:
2380 case OpenHRP::StabilizerService::EEFMQPCOP:
2382 case OpenHRP::StabilizerService::EEFMQPCOP2:
2383 return "EEFMQPCOP2";
2391 std::vector<bool> prev_values;
2392 prev_values.resize(st_bool_values.size());
2393 copy (st_bool_values.begin(), st_bool_values.end(), prev_values.begin());
2394 if (st_bool_values.size() != output_bool_values.length()) {
2395 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" cannot be set. Length " << st_bool_values.size() <<
" != " << output_bool_values.length() << std::endl;
2397 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" cannot be set. Current control_mode is " <<
control_mode << std::endl;
2399 for (
size_t i = 0;
i < st_bool_values.size();
i++) {
2400 st_bool_values[
i] = output_bool_values[
i];
2403 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" is ";
2404 for (
size_t i = 0;
i < st_bool_values.size();
i++) {
2405 std::cerr <<
"[" << st_bool_values[
i] <<
"]";
2407 std::cerr <<
"(set = ";
2408 for (
size_t i = 0;
i < output_bool_values.length();
i++) {
2409 std::cerr <<
"[" << output_bool_values[
i] <<
"]";
2411 std::cerr <<
", prev = ";
2412 for (
size_t i = 0;
i < prev_values.size();
i++) {
2413 std::cerr <<
"[" << prev_values[
i] <<
"]";
2415 std::cerr <<
")" << std::endl;
2420 std::vector<bool> prev_values;
2421 prev_values.resize(st_bool_values.size());
2422 copy (st_bool_values.begin(), st_bool_values.end(), prev_values.begin());
2423 if (st_bool_values.size() != output_bool_values.length()) {
2424 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" cannot be set. Length " << st_bool_values.size() <<
" != " << output_bool_values.length() << std::endl;
2426 for (
size_t i = 0;
i < st_bool_values.size();
i++) {
2427 st_bool_values[
i] = output_bool_values[
i];
2430 std::vector<size_t> failed_indices;
2431 for (
size_t i = 0;
i < st_bool_values.size();
i++) {
2432 if ( (st_bool_values[
i] != output_bool_values[
i]) ) {
2434 st_bool_values[i] = output_bool_values[i];
2436 failed_indices.push_back(i);
2440 if (failed_indices.size() > 0) {
2441 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" cannot be set partially. failed_indices is [";
2442 for (
size_t i = 0;
i < failed_indices.size();
i++) {
2443 std::cerr << failed_indices[
i] <<
" ";
2445 std::cerr <<
"]" << std::endl;
2448 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " << prop_name <<
" is ";
2449 for (
size_t i = 0;
i < st_bool_values.size();
i++) {
2450 std::cerr <<
"[" << st_bool_values[
i] <<
"]";
2452 std::cerr <<
"(set = ";
2453 for (
size_t i = 0;
i < output_bool_values.length();
i++) {
2454 std::cerr <<
"[" << output_bool_values[
i] <<
"]";
2456 std::cerr <<
", prev = ";
2457 for (
size_t i = 0;
i < prev_values.size();
i++) {
2458 std::cerr <<
"[" << prev_values[
i] <<
"]";
2460 std::cerr <<
")" << std::endl;
2479 if (value > ulimit_value) {
2480 return ulimit_value;
2481 }
else if (value < llimit_value) {
2482 return llimit_value;
2490 for (
size_t i = 0;
i < 3;
i++) {
2491 if (value(
i) > ulimit_value) {
2492 ret(
i) = ulimit_value;
2493 }
else if (value(
i) < llimit_value) {
2494 ret(
i) = llimit_value;
2505 for (
size_t i = 0;
i < 3;
i++) {
2506 if (value(
i) > limit_value(
i)) {
2507 ret(
i) = limit_value(
i);
2508 }
else if (value(
i) < -1 * limit_value(
i)) {
2509 ret(
i) = -1 * limit_value(
i);
2520 for (
size_t i = 0;
i < 3;
i++) {
2521 if (value(
i) > ulimit_value(
i)) {
2522 ret(
i) = ulimit_value(
i);
2523 }
else if (value(
i) < llimit_value(
i)) {
2524 ret(
i) = llimit_value(
i);
2534 double gradient, intercept;
2535 if (force < lower_th) {
2537 }
else if (force > upper_th) {
2540 gradient = 1.0 / (upper_th - lower_th);
2541 intercept = -lower_th * gradient;
2542 return gradient * force + intercept;
2548 std::vector<std::string> target_name;
2549 target_name.push_back(
"L_ANKLE_R");
2550 target_name.push_back(
"R_ANKLE_R");
2562 for (
int i = 0;
i <
m_robot->numJoints();
i++ ){
2568 double orgjq =
m_robot->joint(
m_robot->link(
"L_ANKLE_P")->jointId)->q;
2572 m_robot->calcForwardKinematics();
2577 for (
size_t i = 0;
i < 2;
i++) {
2578 target_foot_p[
i] =
m_robot->link(target_name[
i])->p;
2579 target_foot_R[i] =
m_robot->link(target_name[i])->R;
2590 for (
int i = 0;
i <
m_robot->numJoints();
i++ ) {
2615 std::cerr <<
"RPY2 " << tmp(0) <<
" " << tmp(1) << std::endl;
2617 root_p_s = target_root_p + target_root_R * org_cm - root_R_s * org_cm;
2620 m_robot->rootLink()->R = root_R_s;
2621 m_robot->rootLink()->p = root_p_s;
2623 std::cerr <<
" rp " << root_p_s[0] <<
" " << root_p_s[1] <<
" " << root_p_s[2] << std::endl;
2625 m_robot->calcForwardKinematics();
2639 std::cerr <<
"dr " << dr(0) <<
" " << dr(1) <<
" " << dr_vel(0) <<
" " << dr_vel(1) << std::endl;
2640 std::cerr <<
"tau_x " << tau_x << std::endl;
2641 std::cerr <<
"tau_y " << tau_y << std::endl;
2647 double xfront = 0.125;
2651 double mg =
m_robot->totalMass() * 9.8 * 0.9;
2652 double tq_y_ulimit = mg * xrear;
2653 double tq_y_llimit = -1 * mg * xfront;
2654 double tq_x_ulimit = mg * yout;
2655 double tq_x_llimit = mg * yin;
2657 tau_xl[0] = gamma * tau_x;
2658 tau_yl[0] = gamma * tau_y;
2659 tau_xl[0] =
vlimit(tau_xl[0], tq_x_llimit, tq_x_ulimit);
2660 tau_yl[0] =
vlimit(tau_yl[0], tq_y_llimit, tq_y_ulimit);
2662 tau_xl[1]= (1- gamma) * tau_x;
2663 tau_yl[1]= (1- gamma) * tau_y;
2664 tau_xl[1] =
vlimit(tau_xl[1], -1*tq_x_ulimit, -1*tq_x_llimit);
2665 tau_yl[1] =
vlimit(tau_yl[1], tq_y_llimit, tq_y_ulimit);
2672 std::cerr <<
"tq limit " << tq_x_ulimit <<
" " << tq_x_llimit <<
" " << tq_y_ulimit <<
" " << tq_y_llimit << std::endl;
2674 for (
size_t i = 0;
i < 2;
i++) {
2681 std::cerr << i <<
" dleg_x " << dleg_x[i] << std::endl;
2682 std::cerr << i <<
" dleg_y " << dleg_y[i] << std::endl;
2683 std::cerr << i <<
" t_x " <<
m_wrenches[i].data[3] <<
" "<< tau_xl[i] << std::endl;
2684 std::cerr << i <<
" t_y " <<
m_wrenches[i].data[4] <<
" "<< tau_yl[i] << std::endl;
2691 for (
size_t i = 0;
i < 2;
i++) {
2696 target_p[i] = target_foot_p[i];
2703 target_p[0](2) = target_foot_p[0](2);
2704 target_p[1](2) = target_foot_p[1](2);
2707 for (
size_t i = 0;
i < 2;
i++) {
2710 vel_p = target_p[i] - target->
p;
2722 for (
int i = 0;
i < 2;
i++) {
2746 m_robot->calcForwardKinematics();
2751 m_robot->rootLink()->dvo = g - root_w_x_v;
2752 m_robot->rootLink()->dw.setZero();
2756 m_robot->calcInverseDynamics(
m_robot->rootLink(), root_f, root_t);
2779 std::vector<hrp::Vector3> contact_p;
2784 for (
size_t j = 0; j < 3; j++) root_ft(j) = root_f(j);
2785 for (
size_t j = 0; j < 3; j++) root_ft(j+3) = root_t(j);
2787 contact_ft = contact_mat_inv * root_ft;
2794 for (
size_t j = 0; j < 2; j++) {
2799 for (
size_t i = 0;
i < 6;
i++) ft(
i) = contact_ft(
i+j*6);
2801 tq_from_extft = JJ.transpose() * ft;
2835 RTC::Create<Stabilizer>,
2836 RTC::Delete<Stabilizer>);
ComponentProfile m_profile
RTC::TimedPoint3D m_originActCog
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
double get_alpha_cutoff_freq()
png_infop png_charpp int png_charpp profile
RTC::TimedPoint3D m_originRefZmp
hrp::Vector3 eefm_swing_rot_time_const
hrp::Vector3 eefm_pos_damping_gain
void getCurrentParameters()
RTC::OutPort< RTC::TimedPoint3D > m_originActZmpOut
RTC::OutPort< RTC::TimedPoint3D > m_actCPOut
void calc_convex_hull(const std::vector< std::vector< Eigen::Vector2d > > &vs, const std::vector< bool > &cs, const std::vector< hrp::Vector3 > &ee_pos, const std::vector< hrp::Matrix33 > &ee_rot)
std::string getStabilizerAlgorithmString(OpenHRP::StabilizerService::STAlgorithm _st_algorithm)
RTC::TimedDoubleSeq m_tau
RTC::TimedPoint3D m_originNewZmp
RTC::InPort< RTC::TimedDoubleSeq > m_controlSwingSupportTimeIn
static const char * stabilizer_spec[]
std::vector< hrp::Vector3 > rel_ee_pos
void calcSwingSupportLimbGain()
double eefm_body_attitude_control_gain[2]
std::vector< RTC::InPort< RTC::TimedPoint3D > * > m_limbCOPOffsetIn
RTC::OutPort< RTC::TimedDoubleSeq > m_allRefWrenchOut
hrp::Vector3 eefm_rot_time_const
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
double eefm_gravitational_acceleration
hrp::Matrix33 prev_act_foot_origin_rot
OpenHRP::StabilizerService::STAlgorithm st_algorithm
void difference_rotation(hrp::Vector3 &ret_dif_rot, const hrp::Matrix33 &self_rot, const hrp::Matrix33 &target_rot)
bool stringTo(To &val, const char *str)
double swing_support_gain
unsigned int m_debugLevel
hrp::Matrix33 ref_foot_origin_rot
double eefm_body_attitude_control_time_const[2]
RTC::OutPort< RTC::TimedOrientation3D > m_currentBaseRpyOut
std::vector< std::vector< Eigen::Vector2d > > support_polygon_vetices
RTC::OutPort< RTC::TimedLong > m_emergencySignalOut
std::vector< std::vector< Eigen::Vector2d > > margined_support_polygon_vetices
StabilizerService_impl m_service0
RTC::OutPort< RTC::TimedDoubleSeq > m_allEECompOut
hrp::Vector3 eefm_swing_pos_spring_gain
RTC::TimedPoint3D m_originActZmp
RTC::TimedOrientation3D m_currentBaseRpy
RTC::OutPort< RTC::TimedPoint3D > m_refCPOut
double limb_stretch_avoidance_vlimit[2]
RTC::InPort< RTC::TimedDoubleSeq > m_qRefIn
RTC::InPort< RTC::TimedPoint3D > m_sbpCogOffsetIn
static double switching_inpact_absorber(double force, double lower_th, double upper_th)
bool is_inside_foot(const hrp::Vector3 &leg_pos, const bool is_lleg, const double margin=0.0)
std::vector< hrp::Vector3 > ref_moment
static std::ostream & operator<<(std::ostream &os, const struct RTC::Time &tm)
void set_wrench_alpha_blending(const double a)
bool is_front_of_foot(const hrp::Vector3 &leg_pos, const double margin=0.0)
std::vector< RTC::TimedDoubleSeq > m_ref_wrenches
RTC::CorbaPort m_StabilizerServicePort
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
std::vector< RTC::InPort< RTC::TimedDoubleSeq > * > m_wrenchesIn
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::vector< hrp::Vector3 > act_ee_p
hrp::Vector3 eefm_swing_rot_damping_gain
hrp::Vector3 prev_d_rpy_swing
double root_rot_compensation_limit[2]
std::vector< double > eefm_swing_damping_force_thre
void calcDiffFootOriginExtMoment()
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
std::vector< bool > is_ik_enable
std::vector< RTC::TimedPoint3D > m_limbCOPOffset
std::vector< hrp::Vector3 > target_ee_p
std::vector< std::string > rel_ee_name
bool eefm_use_force_difference_control
void StabilizerInit(RTC::Manager *manager)
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
bool is_rear_of_foot(const hrp::Vector3 &leg_pos, const double margin=0.0)
Stabilizer(RTC::Manager *manager)
Constructor.
TwoDofController m_tau_x[2]
RTC::OutPort< RTC::TimedBooleanSeq > m_actContactStatesOut
hrp::Vector3 eefm_swing_pos_damping_gain
bool is_seq_interpolating
std::vector< STIKParam > stikp
std::vector< hrp::Vector3 > act_force
coil::Properties & getProperties()
RTC::InPort< RTC::TimedPoint3D > m_zmpRefIn
void calcContactMatrix(hrp::dmatrix &tm, const std::vector< hrp::Vector3 > &contact_p)
std::vector< bool > act_contact_states
void calcEEForceMomentControl()
std::vector< double > eefm_swing_damping_moment_thre
static Manager & instance()
std::vector< RTC::TimedDoubleSeq > m_wrenches
RTC::TimedPoint3D m_sbpCogOffset
hrp::Vector3 act_total_foot_origin_moment
bool addOutPort(const char *name, OutPortBase &outport)
double eefm_zmp_delay_time_const[2]
std::vector< hrp::Matrix33 > rel_ee_rot
hrp::Vector3 target_ee_diff_p
std::vector< RTC::InPort< RTC::TimedDoubleSeq > * > m_ref_wrenchesIn
bool eefm_use_swing_damping
boost::shared_ptr< Body > BodyPtr
std::vector< bool > is_zmp_calc_enable
std::vector< bool > is_feedback_control_enable
RTC::TimedDoubleSeq m_controlSwingSupportTime
RTC::TimedDoubleSeq m_debugData
RTC::TimedPoint3D m_refCP
std::vector< int > m_will_fall_counter
void distributeZMPToForceMomentsQP(std::vector< hrp::Vector3 > &ref_foot_force, std::vector< hrp::Vector3 > &ref_foot_moment, const std::vector< hrp::Vector3 > &ee_pos, const std::vector< hrp::Vector3 > &cop_pos, const std::vector< hrp::Matrix33 > &ee_rot, const std::vector< std::string > &ee_name, const std::vector< double > &limb_gains, const std::vector< double > &toeheel_ratio, const hrp::Vector3 &new_refzmp, const hrp::Vector3 &ref_zmp, const double total_fz, const double dt, const bool printp=true, const std::string &print_str="", const bool use_cop_distribution=false)
double eefm_pos_time_const_swing
RTC::InPort< RTC::TimedDoubleSeq > m_qCurrentIn
RTC::TimedDoubleSeq m_allEEComp
RTC::OutPort< RTC::TimedDoubleSeq > m_debugDataOut
void getTargetParameters()
Matrix33 rotFromRpy(const Vector3 &rpy)
hrp::Matrix33 target_ee_diff_r
bool isContact(const size_t idx)
RTC::OutPort< RTC::TimedPoint3D > m_originActCogOut
std::vector< std::string > vstring
void getActualParameters()
coil::Properties & getConfig()
OpenHRP::StabilizerService::EmergencyCheckMode emergency_check_mode
hrp::Matrix33 current_root_R
RTC::TimedPoint3D m_originRefCog
void calcJacobian(dmatrix &out_J, const Vector3 &local_p=Vector3::Zero()) const
hrp::dvector transition_joint_q
hrp::Vector3 ref_total_force
void rotm3times(hrp::Matrix33 &m12, const hrp::Matrix33 &m1, const hrp::Matrix33 &m2)
RTC::TimedPoint3D m_zmpRef
void set_leg_inside_margin(const double a)
ExecutionContextHandle_t UniqueId
void moveBasePosRotForBodyRPYControl()
void startStabilizer(void)
void getParameter(OpenHRP::StabilizerService::stParam &i_stp)
std::vector< bool > ref_contact_states
void set_leg_front_margin(const double a)
void calcStateForEmergencySignal()
virtual ~Stabilizer()
Destructor.
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
coil::Guard< coil::Mutex > Guard
RTC::OutPort< RTC::TimedDoubleSeq > m_qRefOut
int calcMaxTransitionCount()
RTC::OutPort< RTC::TimedDoubleSeq > m_COPInfoOut
def j(str, encoding="cp932")
void setBoolSequenceParam(std::vector< bool > &st_bool_values, const OpenHRP::StabilizerService::BoolSequence &output_bool_values, const std::string &prop_name)
int calcSRInverse(const dmatrix &_a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w)
double update(double _x, double _xd)
double get_leg_front_margin()
RTC::TimedPoint3D m_basePos
Link * joint(int index) const
std::vector< double > cp_check_margin
hrp::Vector3 prev_act_cog
std::vector< double > tilt_margin
double eefm_pos_margin_time
void calcFootOriginCoords(hrp::Vector3 &foot_origin_pos, hrp::Matrix33 &foot_origin_rot)
double get_leg_outside_margin()
RTC::OutPort< RTC::TimedPoint3D > m_originNewZmpOut
RTC::OutPort< RTC::TimedPoint3D > m_diffFootOriginExtMomentOut
boost::shared_ptr< FirstOrderLowPassFilter< hrp::Vector3 > > target_ee_diff_p_filter
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
hrp::Vector3 ref_total_moment
hrp::Vector3 eefm_rot_damping_gain
int detection_count_to_air
RTC::OutPort< RTC::TimedPoint3D > m_originRefCogOut
bool initial_cp_too_large_error
boost::shared_ptr< FirstOrderLowPassFilter< hrp::Vector3 > > target_ee_diff_r_filter
void set_vertices_from_margin_params()
RTC::InPort< RTC::TimedPoint3D > m_basePosIn
double get_leg_rear_margin()
unsigned int numJoints() const
void setErrorPrefix(const std::string &_error_prefix)
enum Stabilizer::cmode control_mode
hrp::Vector3 eefm_swing_rot_spring_gain
RTC::TimedBooleanSeq m_contactStates
std::vector< double > toeheel_ratio
std::map< std::string, size_t > contact_states_index_map
hrp::Vector3 prev_ref_cog
hrp::Vector3 eefm_pos_time_const_support
double get_wrench_alpha_blending()
boost::shared_ptr< FirstOrderLowPassFilter< hrp::Vector3 > > act_cogvel_filter
hrp::Matrix33 target_root_R
RTC::TimedOrientation3D m_actBaseRpy
hrp::Vector3 target_root_p
hrp::Vector3 foot_origin_offset[2]
std::vector< double > prev_act_force_z
double eefm_pos_transition_time
RTC::TimedOrientation3D m_baseRpy
SimpleZMPDistributor * szd
hrp::Vector3 current_base_pos
void setParameter(const OpenHRP::StabilizerService::stParam &i_stp)
RTC::TimedDoubleSeq m_toeheelRatio
void distributeZMPToForceMomentsPseudoInverse2(std::vector< hrp::Vector3 > &ref_foot_force, std::vector< hrp::Vector3 > &ref_foot_moment, const std::vector< hrp::Vector3 > &ee_pos, const std::vector< hrp::Vector3 > &cop_pos, const std::vector< hrp::Matrix33 > &ee_rot, const std::vector< std::string > &ee_name, const std::vector< double > &limb_gains, const std::vector< double > &toeheel_ratio, const hrp::Vector3 &new_refzmp, const hrp::Vector3 &ref_zmp, const hrp::Vector3 &total_force, const hrp::Vector3 &total_moment, const std::vector< hrp::dvector6 > &ee_forcemoment_distribution_weight, const double total_fz, const double dt, const bool printp=true, const std::string &print_str="")
std::vector< hrp::Vector3 > projected_normal
RTC::InPort< RTC::TimedBoolean > m_walkingStatesIn
RTC::OutPort< RTC::TimedPoint3D > m_currentBasePosOut
hrp::Vector3 act_base_rpy
double limb_stretch_avoidance_time_const
double eefm_rot_compensation_limit
HRP_UTIL_EXPORT Vector3 rpyFromRot(const Matrix33 &m)
bool calcZMP(hrp::Vector3 &ret_zmp, const double zmp_z)
void stabilizer(Stabilizer *i_stabilizer)
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
void get_margined_vertices(std::vector< std::vector< Eigen::Vector2d > > &vs)
Vector3 cross(const Vector3 &v1, const Vector3 &v2)
std::vector< bool > prev_ref_contact_states
void distributeZMPToForceMoments(std::vector< hrp::Vector3 > &ref_foot_force, std::vector< hrp::Vector3 > &ref_foot_moment, const std::vector< hrp::Vector3 > &ee_pos, const std::vector< hrp::Vector3 > &cop_pos, const std::vector< hrp::Matrix33 > &ee_rot, const std::vector< std::string > &ee_name, const std::vector< double > &limb_gains, const std::vector< double > &toeheel_ratio, const hrp::Vector3 &new_refzmp, const hrp::Vector3 &ref_zmp, const double total_fz, const double dt, const bool printp=true, const std::string &print_str="")
virtual RTC::ReturnCode_t onFinalize()
double vlimit(double value, double llimit_value, double ulimit_value)
void print_params(const std::string &str)
void setBoolSequenceParamWithCheckContact(std::vector< bool > &st_bool_values, const OpenHRP::StabilizerService::BoolSequence &output_bool_values, const std::string &prop_name)
bool is_inside_support_polygon(Eigen::Vector2d &p, const hrp::Vector3 &offset=hrp::Vector3::Zero(), const bool &truncate_p=false, const std::string &str="")
RTC::TimedPoint3D m_actCP
void set_leg_outside_margin(const double a)
double calcDampingControl(const double tau_d, const double tau, const double prev_d, const double DD, const double TT)
RTC::TimedPoint3D m_originActCogVel
void registerInPort(const char *name, InPortBase &inport)
RTC::InPort< RTC::TimedOrientation3D > m_baseRpyIn
virtual RTC::ReturnCode_t onInitialize()
hrp::Matrix33 prev_ref_foot_origin_rot
RTC::TimedDoubleSeq m_qRef
void get_vertices(std::vector< std::vector< Eigen::Vector2d > > &vs)
RTC::InPort< RTC::TimedDoubleSeq > m_toeheelRatioIn
RTC::TimedDoubleSeq m_allRefWrench
double limb_length_margin
RTC::TimedDoubleSeq m_qCurrent
void set_vertices(const std::vector< std::vector< Eigen::Vector2d > > &vs)
RTC::TimedOrientation3D m_rpy
void calcSwingEEModification()
void set_alpha_cutoff_freq(const double a)
double get_leg_inside_margin()
bool addPort(PortBase &port)
RTC::OutPort< RTC::TimedPoint3D > m_originRefZmpOut
virtual bool write(DataType &value)
std::vector< hrp::Matrix33 > target_ee_R
double transition_smooth_gain
bool use_limb_stretch_avoidance
void stopStabilizer(void)
hrp::Vector3 current_root_p
RTC::TimedDoubleSeq m_COPInfo
RTC::TimedBooleanSeq m_actContactStates
hrp::Vector3 diff_foot_origin_ext_moment
std::vector< hrp::JointPathExPtr > jpe_v
RTC::InPort< RTC::TimedBooleanSeq > m_contactStatesIn
hrp::Vector3 prev_ref_zmp
hrp::Vector3 ref_total_foot_origin_moment
std::vector< hrp::Vector3 > ref_force
RTC::InPort< RTC::TimedOrientation3D > m_rpyIn
RTC::TimedPoint3D m_diffFootOriginExtMoment
hrp::dvector6 eefm_ee_forcemoment_distribution_weight
RTC::OutPort< RTC::TimedPoint3D > m_zmpOut
void set_leg_rear_margin(const double a)
void print_vertices(const std::string &str)
hrp::Vector3 eefm_swing_pos_time_const
double contact_decision_threshold
bool addInPort(const char *name, InPortBase &inport)
void distributeZMPToForceMomentsPseudoInverse(std::vector< hrp::Vector3 > &ref_foot_force, std::vector< hrp::Vector3 > &ref_foot_moment, const std::vector< hrp::Vector3 > &ee_pos, const std::vector< hrp::Vector3 > &cop_pos, const std::vector< hrp::Matrix33 > &ee_rot, const std::vector< std::string > &ee_name, const std::vector< double > &limb_gains, const std::vector< double > &toeheel_ratio, const hrp::Vector3 &new_refzmp, const hrp::Vector3 &ref_zmp, const double total_fz, const double dt, const bool printp=true, const std::string &print_str="", const bool use_cop_distribution=true, const std::vector< bool > is_contact_list=std::vector< bool >())
bool reset_emergency_flag
void limbStretchAvoidanceControl(const std::vector< hrp::Vector3 > &ee_p, const std::vector< hrp::Matrix33 > &ee_R)
hrp::Vector3 eefm_ee_moment_limit
png_infop png_uint_32 flag
RTC::OutPort< RTC::TimedOrientation3D > m_actBaseRpyOut
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
RTC::TimedLong m_emergencySignal
hrp::Vector3 sbp_cog_offset
TwoDofController m_tau_y[2]
RTC::OutPort< RTC::TimedDoubleSeq > m_tauOut
RTC::TimedPoint3D m_originRefCogVel
hrp::Vector3 ee_d_foot_pos
RTC::OutPort< RTC::TimedPoint3D > m_originActCogVelOut
hrp::Matrix33 target_foot_origin_rot
RTC::InPort< RTC::TimedDoubleSeq > m_qRefSeqIn
RTC::OutPort< RTC::TimedPoint3D > m_diffCPOut
hrp::Vector3 ee_d_foot_rpy
void mid_coords(coordinates &mid_coords, const double p, const coordinates &c1, const coordinates &c2, const double eps)
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
int usleep(useconds_t usec)
hrp::Vector3 prev_d_pos_swing
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)
hrp::Vector3 current_base_rpy
RTC::TimedBoolean m_walkingStates
RTC::OutPort< RTC::TimedPoint3D > m_originRefCogVelOut
RTC::TimedPoint3D m_diffCP
double eefm_pos_compensation_limit
RTC::TimedPoint3D m_currentBasePos
std::vector< hrp::Matrix33 > act_ee_R
bool is_estop_while_walking