12 #include <hrpModel/Sensor.h> 13 #include <hrpModel/ModelLoaderUtil.h> 17 #include "hrpsys/util/Hrpsys.h" 27 "implementation_id",
"AutoBalancer",
28 "type_name",
"AutoBalancer",
29 "description",
"autobalancer component",
30 "version", HRPSYS_PACKAGE_VERSION,
32 "category",
"example",
33 "activity_type",
"DataFlowComponent",
36 "lang_type",
"compile",
38 "conf.default.debugLevel",
"0",
43 static std::ostream&
operator<<(std::ostream& os,
const struct RTC::Time &tm)
45 int pre = os.precision();
46 os.setf(std::ios::fixed);
47 os << std::setprecision(6)
48 << (tm.sec + tm.nsec/1e9)
49 << std::setprecision(pre);
50 os.unsetf(std::ios::fixed);
57 m_qRefIn(
"qRef", m_qRef),
58 m_basePosIn(
"basePosIn", m_basePos),
59 m_baseRpyIn(
"baseRpyIn", m_baseRpy),
60 m_zmpIn(
"zmpIn", m_zmp),
61 m_optionalDataIn(
"optionalData", m_optionalData),
62 m_emergencySignalIn(
"emergencySignal", m_emergencySignal),
63 m_diffCPIn(
"diffCapturePoint", m_diffCP),
64 m_refFootOriginExtMomentIn(
"refFootOriginExtMoment", m_refFootOriginExtMoment),
65 m_refFootOriginExtMomentIsHoldValueIn(
"refFootOriginExtMomentIsHoldValue", m_refFootOriginExtMomentIsHoldValue),
66 m_actContactStatesIn(
"actContactStates", m_actContactStates),
68 m_zmpOut(
"zmpOut", m_zmp),
69 m_basePosOut(
"basePosOut", m_basePos),
70 m_baseRpyOut(
"baseRpyOut", m_baseRpy),
71 m_baseTformOut(
"baseTformOut", m_baseTform),
72 m_basePoseOut(
"basePoseOut", m_basePose),
73 m_accRefOut(
"accRef", m_accRef),
74 m_contactStatesOut(
"contactStates", m_contactStates),
75 m_toeheelRatioOut(
"toeheelRatio", m_toeheelRatio),
76 m_controlSwingSupportTimeOut(
"controlSwingSupportTime", m_controlSwingSupportTime),
77 m_walkingStatesOut(
"walkingStates", m_walkingStates),
78 m_sbpCogOffsetOut(
"sbpCogOffset", m_sbpCogOffset),
79 m_cogOut(
"cogOut", m_cog),
80 m_AutoBalancerServicePort(
"AutoBalancerService"),
96 std::cerr <<
"[" <<
m_profile.instance_name <<
"] onInitialize()" << std::endl;
147 std::string nameServer = rtcManager.
getConfig()[
"corba.nameservers"];
148 int comPos = nameServer.find(
",");
150 comPos = nameServer.length();
152 nameServer = nameServer.substr(0, comPos);
155 CosNaming::NamingContext::_duplicate(
naming.getRootContext())
157 std::cerr <<
"[" <<
m_profile.instance_name <<
"] failed to load model[" << prop[
"model"] <<
"]" << std::endl;
158 return RTC::RTC_ERROR;
181 size_t prop_num = 10;
182 if (end_effectors_str.size() > 0) {
183 size_t num = end_effectors_str.size()/prop_num;
184 for (
size_t i = 0;
i < num;
i++) {
185 std::string ee_name, ee_target, ee_base;
191 for (
size_t j = 0;
j < 3;
j++) {
195 for (
int j = 0;
j < 4;
j++ ) {
198 tp.
localR = Eigen::AngleAxis<double>(tmpv[3],
hrp::Vector3(tmpv[0], tmpv[1], tmpv[2])).toRotationMatrix();
211 fik->ikp.insert(std::pair<std::string, SimpleFullbodyInverseKinematicsSolver::IKparam>(ee_name, tmp_fikp));
216 if (
m_robot->link(ee_target)->sensors.size() == 0) {
217 std::vector<double> optw(
fik->ikp[ee_name].manip->numJoints(), 1.0);
219 fik->ikp[ee_name].manip->setOptionalWeightVector(optw);
225 ikp.insert(std::pair<std::string, ABCIKparam>(ee_name , tp));
226 ee_vec.push_back(ee_name);
227 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << ee_name <<
"]" << std::endl;
228 std::cerr <<
"[" <<
m_profile.instance_name <<
"] target = " <<
ikp[ee_name].target_link->name <<
", base = " << ee_base << std::endl;
229 std::cerr <<
"[" <<
m_profile.instance_name <<
"] offset_pos = " << tp.
localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
230 std::cerr <<
"[" <<
m_profile.instance_name <<
"] has_toe_joint = " << (tp.
has_toe_joint?
"true":
"false") << std::endl;
235 if (
ikp.find(
"rleg") !=
ikp.end() &&
ikp.find(
"lleg") !=
ikp.end()) {
239 if (
ikp.find(
"rarm") !=
ikp.end() &&
ikp.find(
"larm") !=
ikp.end()) {
247 std::vector<hrp::Vector3> leg_pos;
248 if (leg_offset_str.size() > 0) {
251 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abc_leg_offset = " << leg_offset.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
255 if (leg_pos.size() <
ikp.size()) {
256 size_t tmp_leg_pos_size = leg_pos.size();
257 for (
size_t i = 0;
i <
ikp.size() - tmp_leg_pos_size;
i++) {
258 leg_pos.push_back(hrp::Vector3::Zero());
262 std::vector<std::pair<hrp::Link*, hrp::Link*> > interlocking_joints;
264 if (interlocking_joints.size() > 0) {
265 fik->initializeInterlockingJoints(interlocking_joints);
283 double stride_fwd_x_limit = 0.15;
284 double stride_outside_y_limit = 0.05;
285 double stride_outside_th_limit = 10;
286 double stride_bwd_x_limit = 0.05;
287 double stride_inside_y_limit = stride_outside_y_limit*0.5;
288 double stride_inside_th_limit = stride_outside_th_limit*0.5;
289 std::cerr <<
"[" <<
m_profile.instance_name <<
"] abc_stride_parameter : " << stride_fwd_x_limit <<
"[m], " << stride_outside_y_limit <<
"[m], " << stride_outside_th_limit <<
"[deg], " << stride_bwd_x_limit <<
"[m]" << std::endl;
293 if (leg_offset_str.size() > 0) {
295 stride_bwd_x_limit, stride_inside_y_limit, stride_inside_th_limit));
306 unsigned int nvforce =
m_vfs.size();
307 unsigned int nforce = npforce + nvforce;
310 std::cerr <<
"[" <<
m_profile.instance_name <<
"] WARNING! This robot model has less force sensors(" << nforce;
311 std::cerr <<
") than end-effector settings(" <<
m_contactStates.data.length() <<
") !" << std::endl;
320 for (
unsigned int i=0;
i<npforce;
i++){
323 for (
unsigned int i=0;
i<nvforce;
i++){
324 for ( std::map<std::string, hrp::VirtualForceSensorParam>::iterator it =
m_vfs.begin(); it !=
m_vfs.end(); it++ ) {
325 if (it->second.id == (
int)
i)
sensor_names.push_back(it->first);
329 std::cerr <<
"[" <<
m_profile.instance_name <<
"] force sensor ports (" << nforce <<
")" << std::endl;
330 for (
unsigned int i=0;
i<nforce;
i++){
334 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << std::string(
"ref_"+
sensor_names[i]) << std::endl;
339 for (
unsigned int i=0;
i<nforce;
i++){
345 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << std::string(
sensor_names[i]) << std::endl;
348 std::cerr <<
"[" <<
m_profile.instance_name <<
"] limbCOPOffset ports (" << nforce <<
")" << std::endl;
349 for (
unsigned int i=0;
i<nforce;
i++){
354 std::cerr <<
"[" <<
m_profile.instance_name <<
"] name = " << nm << std::endl;
361 if (
ikp.find(
"rleg") !=
ikp.end() &&
ikp.find(
"lleg") !=
ikp.end()) {
379 std::cerr <<
"[" <<
m_profile.instance_name <<
"] WARNING! This robot model has no GyroSensor named 'gyrometer'! " << std::endl;
414 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onActivated(" << ec_id <<
")" << std::endl;
421 std::cerr <<
"[" <<
m_profile.instance_name<<
"] onDeactivated(" << ec_id <<
")" << std::endl;
425 double tmp_ratio = 0.0;
431 #define DEBUGP ((m_debugLevel==1 && loop%200==0) || m_debugLevel > 1 ) 433 #define DEBUGP2 (false) 491 gg->set_act_contact_states(tmp_contacts);
501 fik->storeCurrentParameters();
505 if (!is_transition_interpolator_empty) {
531 fik->d_root_height = 0.0;
534 if (!is_transition_interpolator_empty) {
540 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ) {
543 for (
unsigned int i=0;
i<
m_force.size();
i++) {
544 for (
unsigned int j=0;
j<6;
j++) {
555 ref_basePos =
m_robot->rootLink()->p;
556 ref_baseRot =
m_robot->rootLink()->R;
563 <<
"] Finished cleanup" << std::endl;
569 if (
m_qRef.data.length() != 0 ) {
571 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
605 m_zmp.data.x = rel_ref_zmp(0);
606 m_zmp.data.y = rel_ref_zmp(1);
607 m_zmp.data.z = rel_ref_zmp(2);
669 for (
unsigned int i = 0;
i <
m_robot->numJoints();
i++ ){
672 fik->setReferenceJointAngles();
676 m_robot->calcForwardKinematics();
677 gg->proc_zmp_weight_map_interpolation();
685 gg->get_swing_support_mid_coords(tmp_fix_coords);
709 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
711 it->second.target_p0 = it->second.target_link->p + it->second.target_link->R * it->second.localPos;
712 it->second.target_r0 = it->second.target_link->R * it->second.localR;
740 ref_zmp(2) = tmp_foot_mid_pos(2);
744 std::vector<coordinates> tmp_end_coords_list;
745 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
747 tmp_end_coords_list.push_back(
coordinates(it->second.target_link->p+it->second.target_link->R*it->second.localPos, it->second.target_link->R*it->second.localR));
753 for (
unsigned int i=0;
i<
m_force.size();
i++) {
754 for (
unsigned int j=0;
j<6;
j++) {
765 for (std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++) {
770 gg->get_swing_support_ee_coords_from_ee_name(it->second.target_p0, it->second.target_r0, it->first);
772 m_contactStates.data[idx] =
gg->get_current_support_state_from_ee_name(it->first);
777 gg->get_swing_support_foot_zmp_offsets_from_ee_name(tmpzmpoff, it->first);
783 gg->get_current_toe_heel_ratio_from_ee_name(tmp, it->first);
787 it->second.target_p0 = it->second.target_link->p + it->second.target_link->R * it->second.localPos;
788 it->second.target_r0 = it->second.target_link->R * it->second.localR;
806 for (std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++) {
812 it->second.target_p0 = it->second.target_link->p + it->second.target_link->R * it->second.localPos;
813 it->second.target_r0 = it->second.target_link->R * it->second.localR;
816 std::vector<std::string>::const_iterator dst = std::find_if(
leg_names.begin(),
leg_names.end(), (boost::lambda::_1 == it->first));
839 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
849 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
863 double *default_zmp_offsets_output =
new double[
ikp.size()*3];
865 for (
size_t i = 0;
i <
ikp.size();
i++)
866 for (
size_t j = 0;
j < 3;
j++)
868 delete[] default_zmp_offsets_output;
870 std::cerr <<
"[" <<
m_profile.instance_name <<
"] default_zmp_offsets (interpolated)" << std::endl;
871 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
888 ikp[
"rleg"].target_p0 = (1-tmp) *
ikp[
"rleg"].adjust_interpolation_org_p0 + tmp*
ikp[
"rleg"].adjust_interpolation_target_p0;
889 ikp[
"lleg"].target_p0 = (1-tmp) *
ikp[
"lleg"].adjust_interpolation_org_p0 + tmp*
ikp[
"lleg"].adjust_interpolation_target_p0;
890 rats::mid_rot(
ikp[
"rleg"].target_r0, tmp,
ikp[
"rleg"].adjust_interpolation_org_r0,
ikp[
"rleg"].adjust_interpolation_target_r0);
891 rats::mid_rot(
ikp[
"lleg"].target_r0, tmp,
ikp[
"lleg"].adjust_interpolation_org_r0,
ikp[
"lleg"].adjust_interpolation_target_r0);
893 tmprc.
pos =
ikp[
"rleg"].target_p0;
894 tmprc.
rot =
ikp[
"rleg"].target_r0;
895 tmplc.
pos =
ikp[
"lleg"].target_p0;
896 tmplc.
rot =
ikp[
"lleg"].target_r0;
930 bool is_hand_control_while_walking =
false;
931 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
933 && it->first.find(
"arm") != std::string::npos ) {
934 is_hand_control_while_walking =
true;
937 if (is_hand_control_while_walking) {
944 dif_p = tmp_fix_coords.
rot.transpose() * dif_p;
946 dif_p = tmp_fix_coords.
rot * dif_p;
948 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
950 && it->first.find(
"arm") != std::string::npos ) {
951 it->second.target_p0 = it->second.target_p0 + dif_p;
962 std::vector<hrp::Vector3> ee_pos;
968 if (alpha>1.0) alpha = 1.0;
969 if (alpha<0.0) alpha = 0.0;
971 std::cerr <<
"[" <<
m_profile.instance_name <<
"] alpha:" << alpha << std::endl;
973 double mg =
m_robot->totalMass() *
gg->get_gravitational_acceleration();
974 m_force[0].data[2] = alpha * mg;
975 m_force[1].data[2] = (1-alpha) * mg;
986 std::map<leg_type, std::string> leg_type_map =
gg->get_leg_type_map();
987 std::map<leg_type, double> zmp_weight_map =
gg->get_zmp_weight_map();
988 double sum_of_weight = 0.0;
992 std::map<leg_type, std::string>::const_iterator dst = std::find_if(leg_type_map.begin(), leg_type_map.end(), (&boost::lambda::_1->* &std::map<leg_type, std::string>::value_type::second == leg_names[
i]));
994 sum_of_weight += zmp_weight_map[dst->first];
996 tmp_foot_mid_pos *= (1.0 / sum_of_weight);
997 return tmp_foot_mid_pos;
1003 if (
gg_is_walking &&
gg->get_lcg_count() ==
gg->get_overwrite_check_timing()+2 ) {
1005 gg->set_offset_velocity_param(vel_htc(0), vel_htc(1) ,vel_htc(2));
1015 fik->overwrite_ref_ja_index_vec.clear();
1017 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
1018 if (it->second.is_active && it->second.has_toe_joint &&
gg->get_use_toe_joint()) {
1019 int i = it->second.target_link->jointId;
1020 if (
gg->get_swing_leg_names().front() == it->first) {
1021 fik->qrefv[i] =
fik->qrefv[i] + -1 *
gg->get_foot_dif_rot_angle();
1023 fik->overwrite_ref_ja_index_vec.push_back(i);
1031 if (fabs(vv.norm()-0.0) < 1e-5) {
1034 Eigen::AngleAxis<double> tmpr(std::asin(vv.norm()), vv.normalized());
1035 return tmpr.toRotationMatrix() * rot;
1042 std::vector<coordinates> foot_coords;
1053 hrp::Matrix33 tmpR (fix_rot * current_foot_mid_rot.transpose());
1054 m_robot->rootLink()->p = fix_pos + tmpR * (
m_robot->rootLink()->p - current_foot_mid_pos);
1056 m_robot->calcForwardKinematics();
1071 tmp_fix_coords.
rot(0,0) = xv1(0); tmp_fix_coords.
rot(1,0) = xv1(1); tmp_fix_coords.
rot(2,0) = xv1(2);
1072 tmp_fix_coords.
rot(0,1) = yv1(0); tmp_fix_coords.
rot(1,1) = yv1(1); tmp_fix_coords.
rot(2,1) = yv1(2);
1073 tmp_fix_coords.
rot(0,2) = ez(0); tmp_fix_coords.
rot(1,2) = ez(1); tmp_fix_coords.
rot(2,2) = ez(2);
1083 for ( std::map<std::string, SimpleFullbodyInverseKinematicsSolver::IKparam>::iterator it =
fik->ikp.begin(); it !=
fik->ikp.end(); it++ ) {
1084 it->second.target_p0 =
ikp[it->first].target_p0;
1085 it->second.target_r0 =
ikp[it->first].target_r0;
1089 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
1090 fik->ikp[it->first].is_ik_enable = it->second.is_active;
1093 fik->revertRobotStateToCurrent();
1140 std::cerr <<
"[" <<
m_profile.instance_name <<
"] start auto balancer mode" << std::endl;
1142 double tmp_ratio = 0.0;
1148 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
1149 it->second.is_active =
false;
1152 for (
size_t i = 0;
i < limbs.length();
i++) {
1155 std::cerr <<
"[" <<
m_profile.instance_name <<
"] limb [" << std::string(limbs[i]) <<
"]" << std::endl;
1163 std::cerr <<
"[" <<
m_profile.instance_name <<
"] stop auto balancer mode" << std::endl;
1165 double tmp_ratio = 1.0;
1176 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Cannot start walking without MODE_ABC. Please startAutoBalancer." << std::endl;
1181 fik->resetIKFailParam();
1182 std::vector<std::string> init_swing_leg_names(
gg->get_footstep_front_leg_names());
1183 std::vector<std::string> tmp_all_limbs(
leg_names);
1184 std::vector<std::string> init_support_leg_names;
1185 std::sort(tmp_all_limbs.begin(), tmp_all_limbs.end());
1186 std::sort(init_swing_leg_names.begin(), init_swing_leg_names.end());
1187 std::set_difference(tmp_all_limbs.begin(), tmp_all_limbs.end(),
1188 init_swing_leg_names.begin(), init_swing_leg_names.end(),
1189 std::back_inserter(init_support_leg_names));
1190 std::vector<step_node> init_support_leg_steps, init_swing_leg_dst_steps;
1191 for (std::vector<std::string>::iterator it = init_support_leg_names.begin(); it != init_support_leg_names.end(); it++)
1193 for (std::vector<std::string>::iterator it = init_swing_leg_names.begin(); it != init_swing_leg_names.end(); it++)
1196 gg->initialize_gait_parameter(
ref_cog, init_support_leg_steps, init_swing_leg_dst_steps);
1199 while ( !
gg->proc_one_tick() );
1209 std::vector<coordinates> tmp_end_coords_list;
1210 for (std::vector<string>::iterator it =
leg_names.begin(); it !=
leg_names.end(); it++) {
1211 if ((*it).find(
"leg") != std::string::npos) tmp_end_coords_list.push_back(
coordinates(
ikp[*it].target_p0,
ikp[*it].target_r0));
1215 gg->clear_footstep_nodes_list();
1222 fik->resetIKFailParam();
1253 std::vector<coordinates> initial_support_legs_coords;
1254 std::vector<leg_type> initial_support_legs;
1255 bool is_valid_gait_type =
calc_inital_support_legs(y, initial_support_legs_coords, initial_support_legs, start_ref_coords);
1256 if (is_valid_gait_type ==
false)
return false;
1257 bool ret =
gg->go_pos_param_2_footstep_nodes_list(x, y, th,
1258 initial_support_legs_coords,
1260 initial_support_legs,
1263 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Cannot goPos because of invalid timing." << std::endl;
1270 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Cannot goPos while stopping mode." << std::endl;
1280 gg->set_velocity_param(vx, vy, vth);
1283 ref_coords.
pos = (
ikp[
"rleg"].target_p0+
ikp[
"lleg"].target_p0)*0.5;
1284 mid_rot(ref_coords.
rot, 0.5,
ikp[
"rleg"].target_r0,
ikp[
"lleg"].target_r0);
1285 std::vector<leg_type> current_legs;
1288 current_legs.assign (1, vy > 0 ?
RLEG :
LLEG);
1291 current_legs = (vy > 0 ? boost::assign::list_of(
RLEG)(
LARM) : boost::assign::list_of(LLEG)(
RARM)).convert_to_container < std::vector<leg_type> > ();
1294 current_legs = (vy > 0 ? boost::assign::list_of(
RLEG)(
RARM) : boost::assign::list_of(LLEG)(
LARM)).convert_to_container < std::vector<leg_type> > ();
1297 std::cerr <<
"[" <<
m_profile.instance_name <<
"] crawl walk[" <<
gait_type <<
"] is not implemented yet." << std::endl;
1301 std::cerr <<
"[" <<
m_profile.instance_name <<
"] gallop walk[" <<
gait_type <<
"] is not implemented yet." << std::endl;
1305 gg->initialize_velocity_mode(ref_coords, vx, vy, vth, current_legs);
1313 gg->finalize_velocity_mode();
1320 std::cerr <<
"[" <<
m_profile.instance_name <<
"] emergencyStop" << std::endl;
1322 gg->emergency_stop();
1330 std::cerr <<
"[" <<
m_profile.instance_name <<
"] releaseEmergencyStop" << std::endl;
1338 OpenHRP::AutoBalancerService::StepParamsSequence spss;
1339 spss.length(fss.length());
1342 for (
size_t i = 0;
i < spss.length();
i++) {
1343 spss[
i].sps.length(fss[
i].fs.length());
1344 for (
size_t j = 0;
j < spss[
i].sps.length();
j++) {
1345 spss[
i].sps[
j].step_height = ((!
gg_is_walking &&
i==0) ? 0.0 :
gg->get_default_step_height());
1346 spss[i].sps[
j].step_time =
gg->get_default_step_time();
1347 spss[i].sps[
j].toe_angle = ((!
gg_is_walking && i==0) ? 0.0 :
gg->get_toe_angle());
1348 spss[i].sps[
j].heel_angle = ((!
gg_is_walking && i==0) ? 0.0 :
gg->get_heel_angle());
1354 bool AutoBalancer::setFootStepsWithParam(
const OpenHRP::AutoBalancerService::FootstepsSequence& fss,
const OpenHRP::AutoBalancerService::StepParamsSequence& spss, CORBA::Long overwrite_fs_idx)
1357 std::cerr <<
"[" <<
m_profile.instance_name <<
"] setFootStepsList" << std::endl;
1361 step_node initial_support_step, initial_input_step;
1363 std::vector<step_node> initial_support_steps;
1365 if (overwrite_fs_idx <= 0) {
1366 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Invalid overwrite index = " << overwrite_fs_idx << std::endl;
1369 if (!
gg->get_footstep_nodes_by_index(initial_support_steps, overwrite_fs_idx-1)) {
1370 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Invalid overwrite index = " << overwrite_fs_idx << std::endl;
1375 for (
size_t i = 0;
i < fss[0].fs.length();
i++) {
1380 initial_support_step = initial_support_steps.front();
1383 std::map<leg_type, std::string> leg_type_map =
gg->get_leg_type_map();
1384 for (
size_t i = 0;
i < fss[0].fs.length();
i++) {
1385 if (std::string(fss[0].fs[
i].leg) == leg_type_map[initial_support_step.
l_r]) {
1387 memcpy(tmp.
pos.data(), fss[0].fs[
i].pos,
sizeof(double)*3);
1388 tmp.
rot = (Eigen::Quaternion<double>(fss[0].fs[
i].rot[0], fss[0].fs[
i].rot[1], fss[0].fs[
i].rot[2], fss[0].fs[
i].rot[3])).normalized().toRotationMatrix();
1389 initial_input_step =
step_node(std::string(fss[0].fs[
i].leg), tmp, 0, 0, 0, 0);
1395 std::vector< std::vector<coordinates> > fs_vec_list;
1396 std::vector< std::vector<std::string> > leg_name_vec_list;
1397 for (
size_t i = 0;
i < fss.length();
i++) {
1398 std::vector<coordinates> fs_vec;
1399 std::vector<std::string> leg_name_vec;
1400 for (
size_t j = 0;
j < fss[
i].fs.length();
j++) {
1401 std::string leg(fss[
i].fs[
j].leg);
1403 memcpy(tmpfs.
pos.data(), fss[
i].fs[
j].pos,
sizeof(double)*3);
1404 tmpfs.
rot = (Eigen::Quaternion<double>(fss[
i].fs[
j].rot[0], fss[
i].fs[
j].rot[1], fss[
i].fs[
j].rot[2], fss[
i].fs[
j].rot[3])).normalized().toRotationMatrix();
1409 std::cerr <<
"[" <<
m_profile.instance_name <<
"] No such target : " << leg << std::endl;
1412 leg_name_vec.push_back(leg);
1413 fs_vec.push_back(tmpfs);
1415 leg_name_vec_list.push_back(leg_name_vec);
1416 fs_vec_list.push_back(fs_vec);
1418 if (spss.length() != fs_vec_list.size()) {
1419 std::cerr <<
"[" <<
m_profile.instance_name <<
"] StepParam length " << spss.length () <<
" != Footstep length " << fs_vec_list.size() << std::endl;
1422 std::cerr <<
"[" <<
m_profile.instance_name <<
"] print footsteps " << std::endl;
1423 std::vector< std::vector<step_node> > fnsl;
1424 for (
size_t i = 0;
i < fs_vec_list.size();
i++) {
1426 std::vector<step_node> tmp_fns;
1427 for (
size_t j = 0;
j < fs_vec_list.at(
i).size();
j++) {
1428 tmp_fns.push_back(
step_node(leg_name_vec_list[
i][
j], fs_vec_list[
i][j], spss[
i].sps[j].step_height, spss[
i].sps[j].step_time, spss[
i].sps[j].toe_angle, spss[
i].sps[j].heel_angle));
1430 fnsl.push_back(tmp_fns);
1435 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Set overwrite footsteps" << std::endl;
1436 gg->set_overwrite_foot_steps_list(fnsl);
1437 gg->set_overwrite_foot_step_index(overwrite_fs_idx);
1439 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Set normal footsteps" << std::endl;
1440 gg->set_foot_steps_list(fnsl);
1445 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Cannot setFootSteps while walking." << std::endl;
1456 gg->set_offset_velocity_param(0,0,0);
1465 gg->set_offset_velocity_param(0,0,0);
1470 std::cerr <<
"[" <<
m_profile.instance_name <<
"] setGaitGeneratorParam" << std::endl;
1471 if (i_param.stride_parameter.length() == 4) {
1472 gg->set_stride_parameters(i_param.stride_parameter[0], i_param.stride_parameter[1], i_param.stride_parameter[2], i_param.stride_parameter[3],
1473 i_param.stride_parameter[1]*0.5, i_param.stride_parameter[2]*0.5);
1475 gg->set_stride_parameters(i_param.stride_parameter[0], i_param.stride_parameter[1], i_param.stride_parameter[2], i_param.stride_parameter[3],
1476 i_param.stride_parameter[4], i_param.stride_parameter[5]);
1478 std::vector<hrp::Vector3> off;
1479 for (
size_t i = 0;
i < i_param.leg_default_translate_pos.length();
i++) {
1480 off.push_back(
hrp::Vector3(i_param.leg_default_translate_pos[
i][0], i_param.leg_default_translate_pos[
i][1], i_param.leg_default_translate_pos[
i][2]));
1482 gg->set_leg_default_translate_pos(off);
1483 gg->set_default_step_time(i_param.default_step_time);
1484 gg->set_default_step_height(i_param.default_step_height);
1485 gg->set_default_double_support_ratio_before(i_param.default_double_support_ratio/2.0);
1486 gg->set_default_double_support_ratio_after(i_param.default_double_support_ratio/2.0);
1487 gg->set_default_double_support_static_ratio_before(i_param.default_double_support_static_ratio/2.0);
1488 gg->set_default_double_support_static_ratio_after(i_param.default_double_support_static_ratio/2.0);
1489 gg->set_default_double_support_ratio_swing_before(i_param.default_double_support_ratio/2.0);
1490 gg->set_default_double_support_ratio_swing_after(i_param.default_double_support_ratio/2.0);
1506 gg->set_default_orbit_type(
STAIR);
1512 gg->set_default_orbit_type(
CROSS);
1514 gg->set_swing_trajectory_delay_time_offset(i_param.swing_trajectory_delay_time_offset);
1515 gg->set_swing_trajectory_final_distance_weight(i_param.swing_trajectory_final_distance_weight);
1516 gg->set_swing_trajectory_time_offset_xy2z(i_param.swing_trajectory_time_offset_xy2z);
1517 gg->set_stair_trajectory_way_point_offset(
hrp::Vector3(i_param.stair_trajectory_way_point_offset[0], i_param.stair_trajectory_way_point_offset[1], i_param.stair_trajectory_way_point_offset[2]));
1518 gg->set_cycloid_delay_kick_point_offset(
hrp::Vector3(i_param.cycloid_delay_kick_point_offset[0], i_param.cycloid_delay_kick_point_offset[1], i_param.cycloid_delay_kick_point_offset[2]));
1519 gg->set_gravitational_acceleration(i_param.gravitational_acceleration);
1520 gg->set_toe_angle(i_param.toe_angle);
1521 gg->set_heel_angle(i_param.heel_angle);
1522 gg->set_toe_pos_offset_x(i_param.toe_pos_offset_x);
1523 gg->set_heel_pos_offset_x(i_param.heel_pos_offset_x);
1524 gg->set_toe_zmp_offset_x(i_param.toe_zmp_offset_x);
1525 gg->set_heel_zmp_offset_x(i_param.heel_zmp_offset_x);
1526 gg->set_toe_check_thre(i_param.toe_check_thre);
1527 gg->set_heel_check_thre(i_param.heel_check_thre);
1528 std::vector<double> tmp_ratio(i_param.toe_heel_phase_ratio.get_buffer(), i_param.toe_heel_phase_ratio.get_buffer()+i_param.toe_heel_phase_ratio.length());
1529 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ";
1530 gg->set_toe_heel_phase_ratio(tmp_ratio);
1531 gg->set_use_toe_joint(i_param.use_toe_joint);
1532 gg->set_use_toe_heel_transition(i_param.use_toe_heel_transition);
1533 gg->set_use_toe_heel_auto_set(i_param.use_toe_heel_auto_set);
1534 gg->set_zmp_weight_map(boost::assign::map_list_of<leg_type, double>(
RLEG, i_param.zmp_weight_map[0])(
LLEG, i_param.zmp_weight_map[1])(
RARM, i_param.zmp_weight_map[2])(
LARM, i_param.zmp_weight_map[3]));
1535 gg->set_optional_go_pos_finalize_footstep_num(i_param.optional_go_pos_finalize_footstep_num);
1536 gg->set_overwritable_footstep_index_offset(i_param.overwritable_footstep_index_offset);
1537 gg->set_leg_margin(i_param.leg_margin);
1538 gg->set_stride_limitation_for_circle_type(i_param.stride_limitation_for_circle_type);
1539 gg->set_overwritable_stride_limitation(i_param.overwritable_stride_limitation);
1540 gg->set_use_stride_limitation(i_param.use_stride_limitation);
1541 gg->set_footstep_modification_gain(i_param.footstep_modification_gain);
1542 gg->set_modify_footsteps(i_param.modify_footsteps);
1543 gg->set_cp_check_margin(i_param.cp_check_margin);
1544 gg->set_margin_time_ratio(i_param.margin_time_ratio);
1546 gg->set_stride_limitation_type(
SQUARE);
1548 gg->set_stride_limitation_type(
CIRCLE);
1552 gg->print_param(std::string(
m_profile.instance_name));
1558 gg->get_stride_parameters(i_param.stride_parameter[0], i_param.stride_parameter[1], i_param.stride_parameter[2], i_param.stride_parameter[3], i_param.stride_parameter[4], i_param.stride_parameter[5]);
1559 std::vector<hrp::Vector3> off;
1560 gg->get_leg_default_translate_pos(off);
1561 i_param.leg_default_translate_pos.length(off.size());
1562 for (
size_t i = 0;
i < i_param.leg_default_translate_pos.length();
i++) {
1563 i_param.leg_default_translate_pos[
i].length(3);
1564 i_param.leg_default_translate_pos[
i][0] = off[
i](0);
1565 i_param.leg_default_translate_pos[
i][1] = off[
i](1);
1566 i_param.leg_default_translate_pos[
i][2] = off[
i](2);
1568 i_param.default_step_time =
gg->get_default_step_time();
1569 i_param.default_step_height =
gg->get_default_step_height();
1570 i_param.default_double_support_ratio_before =
gg->get_default_double_support_ratio_before();
1571 i_param.default_double_support_ratio_after =
gg->get_default_double_support_ratio_after();
1572 i_param.default_double_support_static_ratio_before =
gg->get_default_double_support_static_ratio_before();
1573 i_param.default_double_support_static_ratio_after =
gg->get_default_double_support_static_ratio_after();
1574 i_param.default_double_support_ratio_swing_before =
gg->get_default_double_support_ratio_swing_before();
1575 i_param.default_double_support_ratio_swing_after =
gg->get_default_double_support_ratio_swing_after();
1576 i_param.default_double_support_ratio = i_param.default_double_support_ratio_before + i_param.default_double_support_ratio_after;
1577 i_param.default_double_support_static_ratio = i_param.default_double_support_static_ratio_before + i_param.default_double_support_static_ratio_after;
1580 }
else if (
gg->get_default_orbit_type() ==
CYCLOID) {
1582 }
else if (
gg->get_default_orbit_type() ==
RECTANGLE) {
1584 }
else if (
gg->get_default_orbit_type() ==
STAIR) {
1590 }
else if (
gg->get_default_orbit_type() ==
CROSS) {
1595 for (
size_t i = 0;
i < 3;
i++) i_param.stair_trajectory_way_point_offset[
i] = tmpv(
i);
1596 tmpv =
gg->get_cycloid_delay_kick_point_offset();
1597 for (
size_t i = 0;
i < 3;
i++) i_param.cycloid_delay_kick_point_offset[
i] = tmpv(
i);
1598 i_param.swing_trajectory_delay_time_offset =
gg->get_swing_trajectory_delay_time_offset();
1599 i_param.swing_trajectory_final_distance_weight =
gg->get_swing_trajectory_final_distance_weight();
1600 i_param.swing_trajectory_time_offset_xy2z =
gg->get_swing_trajectory_time_offset_xy2z();
1601 i_param.gravitational_acceleration =
gg->get_gravitational_acceleration();
1602 i_param.toe_angle =
gg->get_toe_angle();
1603 i_param.heel_angle =
gg->get_heel_angle();
1604 i_param.toe_pos_offset_x =
gg->get_toe_pos_offset_x();
1605 i_param.heel_pos_offset_x =
gg->get_heel_pos_offset_x();
1606 i_param.toe_zmp_offset_x =
gg->get_toe_zmp_offset_x();
1607 i_param.heel_zmp_offset_x =
gg->get_heel_zmp_offset_x();
1608 i_param.toe_check_thre =
gg->get_toe_check_thre();
1609 i_param.heel_check_thre =
gg->get_heel_check_thre();
1610 std::vector<double> ratio(
gg->get_NUM_TH_PHASES(),0.0);
1611 gg->get_toe_heel_phase_ratio(ratio);
1612 for (
int i = 0;
i <
gg->get_NUM_TH_PHASES();
i++) i_param.toe_heel_phase_ratio[
i] = ratio[
i];
1613 i_param.use_toe_joint =
gg->get_use_toe_joint();
1614 i_param.use_toe_heel_transition =
gg->get_use_toe_heel_transition();
1615 i_param.use_toe_heel_auto_set =
gg->get_use_toe_heel_auto_set();
1616 std::map<leg_type, double> tmp_zmp_weight_map =
gg->get_zmp_weight_map();
1617 i_param.zmp_weight_map[0] = tmp_zmp_weight_map[
RLEG];
1618 i_param.zmp_weight_map[1] = tmp_zmp_weight_map[
LLEG];
1619 i_param.zmp_weight_map[2] = tmp_zmp_weight_map[
RARM];
1620 i_param.zmp_weight_map[3] = tmp_zmp_weight_map[
LARM];
1621 i_param.optional_go_pos_finalize_footstep_num =
gg->get_optional_go_pos_finalize_footstep_num();
1622 i_param.overwritable_footstep_index_offset =
gg->get_overwritable_footstep_index_offset();
1623 for (
size_t i=0;
i<4;
i++) {
1624 i_param.leg_margin[
i] =
gg->get_leg_margin(
i);
1626 for (
size_t i=0;
i<5;
i++) {
1627 i_param.stride_limitation_for_circle_type[
i] =
gg->get_stride_limitation_for_circle_type(
i);
1629 for (
size_t i=0;
i<5;
i++) {
1630 i_param.overwritable_stride_limitation[
i] =
gg->get_overwritable_stride_limitation(
i);
1632 i_param.use_stride_limitation =
gg->get_use_stride_limitation();
1633 i_param.footstep_modification_gain =
gg->get_footstep_modification_gain();
1634 i_param.modify_footsteps =
gg->get_modify_footsteps();
1635 for (
size_t i=0;
i<2;
i++) {
1636 i_param.cp_check_margin[
i] =
gg->get_cp_check_margin(
i);
1638 i_param.margin_time_ratio =
gg->get_margin_time_ratio();
1639 if (
gg->get_stride_limitation_type() ==
SQUARE) {
1641 }
else if (
gg->get_stride_limitation_type() ==
CIRCLE) {
1650 std::cerr <<
"[" <<
m_profile.instance_name <<
"] setAutoBalancerParam" << std::endl;
1651 double *default_zmp_offsets_array =
new double[
ikp.size()*3];
1652 for (
size_t i = 0;
i <
ikp.size();
i++)
1653 for (
size_t j = 0;
j < 3;
j++)
1654 default_zmp_offsets_array[
i*3+
j] = i_param.default_zmp_offsets[
i][
j];
1661 std::cerr <<
"[" <<
m_profile.instance_name <<
"] default_zmp_offsets cannot be set because interpolating." << std::endl;
1664 switch (i_param.use_force_mode) {
1665 case OpenHRP::AutoBalancerService::MODE_NO_FORCE:
1668 case OpenHRP::AutoBalancerService::MODE_REF_FORCE:
1671 case OpenHRP::AutoBalancerService::MODE_REF_FORCE_WITH_FOOT:
1674 case OpenHRP::AutoBalancerService::MODE_REF_FORCE_RFU_EXT_MOMENT:
1681 std::cerr <<
"[" <<
m_profile.instance_name <<
"] use_force_mode cannot be changed to [" << i_param.use_force_mode <<
"] during MODE_ABC, MODE_SYNC_TO_IDLE or MODE_SYNC_TO_ABC." << std::endl;
1685 for (
size_t j = 0;
j < 3;
j++)
1687 for (
size_t j = 0;
j < 3;
j++)
1690 i_param.graspless_manip_reference_trans_rot[1],
1691 i_param.graspless_manip_reference_trans_rot[2],
1692 i_param.graspless_manip_reference_trans_rot[3]).normalized().toRotationMatrix());
1694 std::vector<std::string> cur_leg_names, dst_leg_names;
1696 for (
size_t i = 0;
i < i_param.leg_names.length();
i++) {
1697 dst_leg_names.push_back(std::string(i_param.leg_names[
i]));
1699 std::sort(cur_leg_names.begin(), cur_leg_names.end());
1700 std::sort(dst_leg_names.begin(), dst_leg_names.end());
1701 if (cur_leg_names != dst_leg_names) {
1706 double tmp_ratio = 0.0;
1714 std::cerr <<
"[" <<
m_profile.instance_name <<
"] leg_names cannot be set because interpolating." << std::endl;
1720 std::cerr <<
"[" <<
m_profile.instance_name <<
"] is_hand_fix_mode cannot be set in (gg_is_walking = true). Current is_hand_fix_mode is " << (
is_hand_fix_mode?
"true":
"false") << std::endl;
1723 for (
size_t i = 0;
i < i_param.end_effector_list.length();
i++) {
1724 std::map<std::string, ABCIKparam>::iterator it =
ikp.find(std::string(i_param.end_effector_list[
i].leg));
1725 memcpy(it->second.localPos.data(), i_param.end_effector_list[
i].pos,
sizeof(double)*3);
1726 it->second.localR = (Eigen::Quaternion<double>(i_param.end_effector_list[
i].rot[0], i_param.end_effector_list[
i].rot[1], i_param.end_effector_list[
i].rot[2], i_param.end_effector_list[
i].rot[3])).normalized().toRotationMatrix();
1729 std::cerr <<
"[" <<
m_profile.instance_name <<
"] cannot change end-effectors except during MODE_IDLE" << std::endl;
1731 if (i_param.default_gait_type == OpenHRP::AutoBalancerService::BIPED) {
1733 }
else if (i_param.default_gait_type == OpenHRP::AutoBalancerService::TROT) {
1735 }
else if (i_param.default_gait_type == OpenHRP::AutoBalancerService::PACE) {
1737 }
else if (i_param.default_gait_type == OpenHRP::AutoBalancerService::CRAWL) {
1739 }
else if (i_param.default_gait_type == OpenHRP::AutoBalancerService::GALLOP) {
1743 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Ref force balancing" << std::endl;
1745 std::cerr <<
"[" <<
m_profile.instance_name <<
"] additional_force_applied_point_offset and additional_force_applied_link_name cannot be updated during MODE_REF_FORCE_WITH_FOOT and non-MODE_IDLE"<< std::endl;
1746 }
else if ( !
m_robot->link(std::string(i_param.additional_force_applied_link_name)) ) {
1747 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Invalid link name for additional_force_applied_link_name = " << i_param.additional_force_applied_link_name << std::endl;
1750 for (
size_t i = 0;
i < 3;
i++) {
1753 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Link name for additional_force_applied_link_name = " <<
additional_force_applied_link->
name <<
", additional_force_applied_point_offset = " <<
additional_force_applied_point_offset.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
1756 for (std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++) {
1757 std::cerr <<
"[" <<
m_profile.instance_name <<
"] End Effector [" << it->first <<
"]" << std::endl;
1758 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localpos = " << it->second.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) <<
"[m]" << std::endl;
1759 std::cerr <<
"[" <<
m_profile.instance_name <<
"] localR = " << it->second.localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
"\n",
" [",
"]")) << std::endl;
1762 std::cerr <<
"[" <<
m_profile.instance_name <<
"] default_zmp_offsets = ";
1763 for (
size_t i = 0;
i <
ikp.size() * 3;
i++) {
1764 std::cerr << default_zmp_offsets_array[
i] <<
" ";
1766 std::cerr << std::endl;
1767 delete[] default_zmp_offsets_array;
1771 std::cerr <<
"[" <<
m_profile.instance_name <<
"] graspless_manip_p_gain = " <<
graspless_manip_p_gain.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
" [",
"]")) << std::endl;
1775 for (std::vector<std::string>::iterator it =
leg_names.begin(); it !=
leg_names.end(); it++) std::cerr <<
"[" <<
m_profile.instance_name <<
"] leg_names [" << *it <<
"]" << std::endl;
1776 std::cerr <<
"[" <<
m_profile.instance_name <<
"] default_gait_type = " <<
gait_type << std::endl;
1778 fik->move_base_gain = i_param.move_base_gain;
1779 fik->pos_ik_thre = i_param.pos_ik_thre;
1780 fik->rot_ik_thre = i_param.rot_ik_thre;
1783 fik->setIKParam(
ee_vec, i_param.ik_limb_parameters);
1785 fik->use_limb_stretch_avoidance = i_param.use_limb_stretch_avoidance;
1786 fik->limb_stretch_avoidance_time_const = i_param.limb_stretch_avoidance_time_const;
1787 for (
size_t i = 0;
i < 2;
i++) {
1788 fik->limb_stretch_avoidance_vlimit[
i] = i_param.limb_stretch_avoidance_vlimit[
i];
1790 for (
size_t i = 0;
i <
fik->ikp.size();
i++) {
1791 fik->ikp[
ee_vec[
i]].limb_length_margin = i_param.limb_length_margin[
i];
1798 i_param.default_zmp_offsets.length(
ikp.size());
1799 for (
size_t i = 0;
i <
ikp.size();
i++) {
1800 i_param.default_zmp_offsets[
i].length(3);
1801 for (
size_t j = 0;
j < 3;
j++) {
1806 case MODE_IDLE: i_param.controller_mode = OpenHRP::AutoBalancerService::MODE_IDLE;
break;
1807 case MODE_ABC: i_param.controller_mode = OpenHRP::AutoBalancerService::MODE_ABC;
break;
1808 case MODE_SYNC_TO_IDLE: i_param.controller_mode = OpenHRP::AutoBalancerService::MODE_SYNC_TO_IDLE;
break;
1809 case MODE_SYNC_TO_ABC: i_param.controller_mode = OpenHRP::AutoBalancerService::MODE_SYNC_TO_ABC;
break;
1813 case MODE_NO_FORCE: i_param.use_force_mode = OpenHRP::AutoBalancerService::MODE_NO_FORCE;
break;
1814 case MODE_REF_FORCE: i_param.use_force_mode = OpenHRP::AutoBalancerService::MODE_REF_FORCE;
break;
1815 case MODE_REF_FORCE_WITH_FOOT: i_param.use_force_mode = OpenHRP::AutoBalancerService::MODE_REF_FORCE_WITH_FOOT;
break;
1821 for (
size_t j = 0;
j < 3;
j++)
1823 for (
size_t j = 0;
j < 3;
j++)
1826 i_param.graspless_manip_reference_trans_rot[0] = qt.w();
1827 i_param.graspless_manip_reference_trans_rot[1] = qt.x();
1828 i_param.graspless_manip_reference_trans_rot[2] = qt.y();
1829 i_param.graspless_manip_reference_trans_rot[3] = qt.z();
1833 i_param.leg_names.length(
leg_names.size());
1836 i_param.end_effector_list.length(
ikp.size());
1839 for (std::map<std::string, ABCIKparam>::const_iterator it =
ikp.begin(); it !=
ikp.end(); it++) {
1841 coordinates(it->second.localPos, it->second.localR));
1842 i_param.end_effector_list[i].leg = it->first.c_str();
1847 case BIPED: i_param.default_gait_type = OpenHRP::AutoBalancerService::BIPED;
break;
1848 case TROT: i_param.default_gait_type = OpenHRP::AutoBalancerService::TROT;
break;
1849 case PACE: i_param.default_gait_type = OpenHRP::AutoBalancerService::PACE;
break;
1850 case CRAWL: i_param.default_gait_type = OpenHRP::AutoBalancerService::CRAWL;
break;
1851 case GALLOP: i_param.default_gait_type = OpenHRP::AutoBalancerService::GALLOP;
break;
1855 i_param.move_base_gain =
fik->move_base_gain;
1856 i_param.pos_ik_thre =
fik->pos_ik_thre;
1857 i_param.rot_ik_thre =
fik->rot_ik_thre;
1859 fik->getIKParam(
ee_vec, i_param.ik_limb_parameters);
1861 i_param.use_limb_stretch_avoidance =
fik->use_limb_stretch_avoidance;
1862 i_param.limb_stretch_avoidance_time_const =
fik->limb_stretch_avoidance_time_const;
1863 i_param.limb_length_margin.length(
fik->ikp.size());
1864 for (
size_t i = 0;
i < 2;
i++) {
1865 i_param.limb_stretch_avoidance_vlimit[
i] =
fik->limb_stretch_avoidance_vlimit[
i];
1867 for (
size_t i = 0;
i <
ikp.size();
i++) {
1868 i_param.limb_length_margin[
i] =
fik->ikp[
ee_vec[
i]].limb_length_margin;
1871 for (
size_t i = 0;
i < 3;
i++) {
1879 memcpy(out_fs.pos, in_fs.
pos.data(),
sizeof(double)*3);
1880 Eigen::Quaternion<double> qt(in_fs.
rot);
1881 out_fs.rot[0] = qt.w();
1882 out_fs.rot[1] = qt.x();
1883 out_fs.rot[2] = qt.y();
1884 out_fs.rot[3] = qt.z();
1894 if (
gg->get_support_leg_names().front() ==
"rleg") {
1899 switch (
gg->get_current_support_states().front() ) {
1911 <<
"] adjustFootSteps" << std::endl;
1919 ikp[
"rleg"].adjust_interpolation_org_p0 =
ikp[
"rleg"].target_p0;
1920 ikp[
"lleg"].adjust_interpolation_org_p0 =
ikp[
"lleg"].target_p0;
1921 ikp[
"rleg"].adjust_interpolation_org_r0 =
ikp[
"rleg"].target_r0;
1922 ikp[
"lleg"].adjust_interpolation_org_r0 =
ikp[
"lleg"].target_r0;
1924 coordinates(
ikp[
"rleg"].adjust_interpolation_org_p0,
ikp[
"rleg"].adjust_interpolation_org_r0),
1925 coordinates(
ikp[
"lleg"].adjust_interpolation_org_p0,
ikp[
"lleg"].adjust_interpolation_org_r0));
1930 memcpy(eepos.data(), rfootstep.pos,
sizeof(double)*3);
1931 eerot = (Eigen::Quaternion<double>(rfootstep.rot[0], rfootstep.rot[1], rfootstep.rot[2], rfootstep.rot[3])).normalized().toRotationMatrix();
1932 ikp[
"rleg"].adjust_interpolation_target_r0 = eerot;
1933 ikp[
"rleg"].adjust_interpolation_target_p0 = eepos;
1934 memcpy(eepos.data(), lfootstep.pos,
sizeof(double)*3);
1935 eerot = (Eigen::Quaternion<double>(lfootstep.rot[0], lfootstep.rot[1], lfootstep.rot[2], lfootstep.rot[3])).normalized().toRotationMatrix();
1936 ikp[
"lleg"].adjust_interpolation_target_r0 = eerot;
1937 ikp[
"lleg"].adjust_interpolation_target_p0 = eepos;
1939 coordinates(
ikp[
"rleg"].adjust_interpolation_target_p0,
ikp[
"rleg"].adjust_interpolation_target_r0),
1940 coordinates(
ikp[
"lleg"].adjust_interpolation_target_p0,
ikp[
"lleg"].adjust_interpolation_target_r0));
1946 target_mid_rpy(2) = org_mid_rpy(2);
1948 target_mid_coords.
pos = org_mid_coords.
pos;
1951 tmpc = target_mid_coords;
1953 ikp[
"rleg"].adjust_interpolation_target_p0 = tmpc.
pos;
1954 ikp[
"rleg"].adjust_interpolation_target_r0 = tmpc.
rot;
1955 tmpc = target_mid_coords;
1957 ikp[
"lleg"].adjust_interpolation_target_p0 = tmpc.
pos;
1958 ikp[
"lleg"].adjust_interpolation_target_r0 = tmpc.
rot;
1974 std::cerr <<
"[" <<
m_profile.instance_name <<
"] getRemainingFootstepSequence" << std::endl;
1975 o_footstep =
new OpenHRP::AutoBalancerService::FootstepSequence;
1977 std::vector< std::vector<step_node> > fsnl =
gg->get_remaining_footstep_nodes_list();
1978 o_current_fs_idx =
gg->get_footstep_index();
1979 o_footstep->length(fsnl.size());
1980 for (
size_t i = 0;
i < fsnl.size();
i++) {
1981 o_footstep[
i].leg = (fsnl[
i].front().l_r==
RLEG?
"rleg":
"lleg");
1990 std::cerr <<
"[" <<
m_profile.instance_name <<
"] getGoPosFootstepsSequence" << std::endl;
1991 o_footstep =
new OpenHRP::AutoBalancerService::FootstepsSequence;
1993 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Cannot call getGoPosFootstepsSequence in walking" << std::endl;
1997 std::vector< std::vector<step_node> > new_footstep_nodes_list;
1999 std::vector<coordinates> initial_support_legs_coords;
2000 std::vector<leg_type> initial_support_legs;
2001 bool is_valid_gait_type =
calc_inital_support_legs(y, initial_support_legs_coords, initial_support_legs, start_ref_coords);
2002 if (is_valid_gait_type ==
false)
return false;
2004 gg->go_pos_param_2_footstep_nodes_list_core (x, y, th,
2005 initial_support_legs_coords, start_ref_coords, initial_support_legs,
2006 new_footstep_nodes_list,
true, 0);
2007 o_footstep->length(new_footstep_nodes_list.size());
2008 for (
size_t i = 0;
i < new_footstep_nodes_list.size();
i++) {
2009 o_footstep[
i].fs.length(new_footstep_nodes_list.at(
i).size());
2010 for (
size_t j = 0;
j < new_footstep_nodes_list.at(
i).size();
j++) {
2011 leg_type tmp_leg_type = new_footstep_nodes_list.at(
i).at(
j).l_r;
2012 o_footstep[
i].fs[
j].leg = ((tmp_leg_type ==
RLEG) ?
"rleg":
2013 (tmp_leg_type ==
LLEG) ?
"lleg":
2014 (tmp_leg_type ==
RARM) ?
"rarm":
2040 double mass =
m_robot->totalMass();
2041 double mg = mass *
gg->get_gravitational_acceleration();
2042 hrp::Vector3 total_sensor_ref_force = hrp::Vector3::Zero();
2046 hrp::Vector3 total_nosensor_ref_force = mg * hrp::Vector3::UnitZ() - total_sensor_ref_force;
2057 for (
size_t j = 0;
j < 2;
j++) {
2058 nume(
j) = mg * tmpcog(
j);
2062 nume(
j) += (tmp_prev_additional_force_applied_pos(
j)-
additional_force_applied_link->
p(
j))*total_nosensor_ref_force(2) + (
j==0 ? tmp_ext_moment(1):-tmp_ext_moment(0));
2063 denom(
j) -= total_nosensor_ref_force(2);
2065 for ( std::map<std::string, ABCIKparam>::iterator it =
ikp.begin(); it !=
ikp.end(); it++ ) {
2070 hrp::Vector3 fpos = it->second.target_link->p + it->second.target_link->R * it->second.localPos;
2078 nume(
j) += ( (fpos(2) - ref_com_height) * total_nosensor_ref_force(
j) - fpos(
j) * total_nosensor_ref_force(2) );
2079 denom(
j) -= total_nosensor_ref_force(2);
2082 sb_point(
j) = nume(
j) / denom(
j);
2084 sb_point(2) = ref_com_height;
2088 #define rad2deg(rad) (rad * 180 / M_PI) 2091 #define deg2rad(deg) (deg * M_PI / 180) 2098 coordinates ref_hand_coords(
gg->get_dst_foot_midcoords()), act_hand_coords;
2104 act_hand_coords.pos = (rarm_pos+larm_pos)/2.0;
2108 hrp::Vector3 ref_y(ref_hand_coords.rot * hrp::Vector3::UnitY());
2117 dr(0) = 0; dr(1) = 0;
2119 dp = act_hand_coords.pos - ref_hand_coords.pos
2120 + dr.cross(
hrp::Vector3(foot_pos - act_hand_coords.pos));
2130 return hrp::Vector3::Zero();
2137 initial_support_legs_coords.assign (1,
2141 initial_support_legs.assign (1, y > 0 ?
RLEG :
LLEG);
2144 initial_support_legs_coords = (y > 0 ?
2146 : boost::assign::list_of(
coordinates(
ikp[
"lleg"].target_p0,
ikp[
"lleg"].target_r0))(
coordinates(
ikp[
"rarm"].target_p0,
ikp[
"rarm"].target_r0))).convert_to_container < std::vector<coordinates> > ();
2147 initial_support_legs = (y > 0 ? boost::assign::list_of(
RLEG)(
LARM) : boost::assign::list_of(LLEG)(
RARM)).convert_to_container < std::vector<leg_type> > ();
2150 initial_support_legs_coords = (y > 0 ?
2152 : boost::assign::list_of(
coordinates(
ikp[
"lleg"].target_p0,
ikp[
"lleg"].target_r0))(
coordinates(
ikp[
"larm"].target_p0,
ikp[
"larm"].target_r0))).convert_to_container < std::vector<coordinates> > ();
2153 initial_support_legs = (y > 0 ? boost::assign::list_of(
RLEG)(
RARM) : boost::assign::list_of(LLEG)(
LARM)).convert_to_container < std::vector<leg_type> > ();
2156 std::cerr <<
"[" <<
m_profile.instance_name <<
"] crawl walk[" <<
gait_type <<
"] is not implemented yet." << std::endl;
2160 std::cerr <<
"[" <<
m_profile.instance_name <<
"] gallop walk[" <<
gait_type <<
"] is not implemented yet." << std::endl;
2164 start_ref_coords.
pos = (
ikp[
"rleg"].target_p0+
ikp[
"lleg"].target_p0)*0.5;
2165 mid_rot(start_ref_coords.
rot, 0.5,
ikp[
"rleg"].target_r0,
ikp[
"lleg"].target_r0);
2175 hrp::dmatrix W2 = hrp::dmatrix::Zero(W.rows(), W.cols());
2176 for (
size_t i = 0;
i < W.rows();
i++) W2(
i,
i) = std::sqrt(W(
i,
i));
2178 hrp::dmatrix Aw_inv = hrp::dmatrix::Zero(A.cols(), A.rows());
2180 ret = W2 * Aw_inv *
b;
2190 std::vector<hrp::Vector3> cop_pos;
2191 std::vector<double> limb_gains;
2198 size_t state_dim = 6*ee_num;
2199 size_t total_wrench_dim = 5;
2203 hrp::dmatrix Wmat = hrp::dmatrix::Identity(state_dim/2, state_dim/2);
2204 hrp::dmatrix Gmat = hrp::dmatrix::Zero(total_wrench_dim, state_dim/2);
2207 for (
size_t j = 0;
j < ee_num;
j++) {
2208 if (total_wrench_dim == 3) {
2209 Gmat(0,3*
j+2) = 1.0;
2211 for (
size_t k = 0; k < 3; k++) Gmat(k,3*
j+k) = 1.0;
2215 for (
size_t i = 0;
i < total_wrench_dim;
i++) {
2216 for (
size_t j = 0;
j < ee_num;
j++) {
2217 if (
i == total_wrench_dim-2 ) {
2218 Gmat(
i,3*
j+1) = -(cop_pos[
j](2) - tmp_ref_zmp(2));
2219 Gmat(
i,3*
j+2) = (cop_pos[
j](1) - tmp_ref_zmp(1));
2220 }
else if (
i == total_wrench_dim-1 ) {
2221 Gmat(
i,3*
j) = (cop_pos[
j](2) - tmp_ref_zmp(2));
2222 Gmat(
i,3*
j+2) = -(cop_pos[
j](0) - tmp_ref_zmp(0));
2227 for (
size_t j = 0;
j < ee_num;
j++) {
2228 for (
size_t i = 0;
i < 3;
i++) {
2230 Wmat(
i+
j*3,
i+
j*3) = Wmat(
i+
j*3,
i+
j*3) * limb_gains[
j] * (
i==2? 1.0 : 0.01);
2232 Wmat(i+
j*3, i+
j*3) = Wmat(i+
j*3, i+
j*3) * limb_gains[
j];
2239 hrp::dvector total_wrench = hrp::dvector::Zero(total_wrench_dim);
2242 total_wrench(total_wrench_dim-3) = total_fz;
2245 std::cerr <<
"[" <<
m_profile.instance_name <<
"] distributeReferenceZMPToWrenches" << std::endl;
2254 m_force[fidx].data[0] = f_ee(0);
2255 m_force[fidx].data[1] = f_ee(1);
2256 m_force[fidx].data[2] = f_ee(2);
2257 m_force[fidx].data[3] = n_ee(0);
2258 m_force[fidx].data[4] = n_ee(1);
2259 m_force[fidx].data[5] = n_ee(2);
2261 std::cerr <<
"[" <<
m_profile.instance_name <<
"] " 2262 <<
"ref_force [" << leg_names[
i] <<
"] " << f_ee.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N], " 2263 <<
"ref_moment [" << leg_names[
i] <<
"] " << n_ee.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[Nm]" << std::endl;
2267 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Gmat = " << Gmat.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N,Nm]" << std::endl;
2268 std::cerr <<
"[" <<
m_profile.instance_name <<
"] total_wrench = " << total_wrench.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N,Nm]" << std::endl;
2271 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Gmat*ret = " << tmp.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N,Nm]" << std::endl;
2272 std::cerr <<
"[" <<
m_profile.instance_name <<
"] (Gmat*ret-total_wrench) = " << (tmp-total_wrench).format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N,Nm]" << std::endl;
2273 std::cerr <<
"[" <<
m_profile.instance_name <<
"] ret = " << ret.format(Eigen::IOFormat(Eigen::StreamPrecision, 0,
", ",
", ",
"",
"",
"[",
"]")) <<
"[N,Nm]" << std::endl;
2274 std::cerr <<
"[" <<
m_profile.instance_name <<
"] Wmat(diag) = [";
2275 for (
size_t j = 0;
j < ee_num;
j++) {
2276 for (
size_t i = 0;
i < 3;
i++) {
2277 std::cerr << Wmat(
i+
j*3,
i+
j*3) <<
" ";
2280 std::cerr <<
"]" << std::endl;
2287 case OpenHRP::AutoBalancerService::MODE_NO_FORCE:
2288 return "MODE_NO_FORCE";
2289 case OpenHRP::AutoBalancerService::MODE_REF_FORCE:
2290 return "MODE_REF_FORCE";
2291 case OpenHRP::AutoBalancerService::MODE_REF_FORCE_WITH_FOOT:
2292 return "MODE_REF_FORCE_WITH_FOOT";
2293 case OpenHRP::AutoBalancerService::MODE_REF_FORCE_RFU_EXT_MOMENT:
2294 return "MODE_REF_FORCE_RFU_EXT_MOMENT";
2308 RTC::Create<AutoBalancer>,
2309 RTC::Delete<AutoBalancer>);
ComponentProfile m_profile
TimedOrientation3D m_baseRpy
png_infop png_charpp int png_charpp profile
TimedBooleanSeq m_contactStates
TimedDoubleSeq m_toeheelRatio
InPort< TimedBoolean > m_refFootOriginExtMomentIsHoldValueIn
bool graspless_manip_mode
void getOutputParametersForIDLE()
SequenceElement & front(CorbaSequence &seq)
void autobalancer(AutoBalancer *i_autobalancer)
void calculateOutputRefForces()
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
rats::coordinates fix_leg_coords2
void difference_rotation(hrp::Vector3 &ret_dif_rot, const hrp::Matrix33 &self_rot, const hrp::Matrix33 &target_rot)
void multi_mid_coords(coordinates &ret, const std::vector< coordinates > &cs, const double eps)
std::vector< InPort< TimedDoubleSeq > * > m_ref_forceIn
std::vector< std::string > leg_names
bool stringTo(To &val, const char *str)
void fixLegToCoords(const hrp::Vector3 &fix_pos, const hrp::Matrix33 &fix_rot)
static std::ostream & operator<<(std::ostream &os, const struct RTC::Time &tm)
std::map< std::string, ABCIKparam > ikp
InPort< TimedPoint3D > m_basePosIn
void AutoBalancerInit(RTC::Manager *manager)
bool calc_inital_support_legs(const double &y, std::vector< rats::coordinates > &initial_support_legs_coords, std::vector< rats::leg_type > &initial_support_legs, rats::coordinates &start_ref_coords)
OutPort< TimedPoint3D > m_sbpCogOffsetOut
InPort< TimedDoubleSeq > m_optionalDataIn
hrp::Vector3 prev_imu_sensor_pos
OutPort< TimedDoubleSeq > m_controlSwingSupportTimeOut
void copyRatscoords2Footstep(OpenHRP::AutoBalancerService::Footstep &out_fs, const rats::coordinates &in_fs)
double transition_interpolator_ratio
void setName(const std::string &_name)
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::vector< TimedPoint3D > m_limbCOPOffset
interpolator * adjust_footstep_interpolator
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
void transformation(coordinates &tc, coordinates c, const std::string &wrt=":local") const
enum AutoBalancer::@2 gait_type
void interpolateLegNamesAndZMPOffsets()
std::vector< hrp::Vector3 > default_zmp_offsets
boost::shared_ptr< JointPathEx > JointPathExPtr
void transform(const coordinates &c, const std::string &wrt=":local")
virtual RTC::ReturnCode_t onFinalize()
OutPort< TimedDoubleSeq > m_toeheelRatioOut
bool setAutoBalancerParam(const OpenHRP::AutoBalancerService::AutoBalancerParam &i_param)
boost::shared_ptr< SimpleFullbodyInverseKinematicsSolver > fikPtr
coil::Properties & getProperties()
bool getFootstepParam(OpenHRP::AutoBalancerService::FootstepParam &i_param)
boost::shared_ptr< rats::gait_generator > ggPtr
static Manager & instance()
hrp::Link * additional_force_applied_link
hrp::Vector3 calcFootMidPosUsingZMPWeightMap()
static double no_using_toe_heel_ratio
bool addOutPort(const char *name, OutPortBase &outport)
double zmp_transition_time
boost::shared_ptr< Body > BodyPtr
OutPort< TimedBooleanSeq > m_contactStatesOut
void updateWalkingVelocityFromHandError(rats::coordinates &tmp_fix_coords)
Matrix33 rotFromRpy(const Vector3 &rpy)
bool setFootStepsWithParam(const OpenHRP::AutoBalancerService::FootstepSequence &fs, const OpenHRP::AutoBalancerService::StepParamSequence &sps, CORBA::Long overwrite_fs_idx)
OutPort< TimedDoubleSeq > m_baseTformOut
bool adjustFootSteps(const OpenHRP::AutoBalancerService::Footstep &rfootstep, const OpenHRP::AutoBalancerService::Footstep &lfootstep)
void updateTargetCoordsForHandFixMode(rats::coordinates &tmp_fix_coords)
std::vector< std::string > vstring
void setMatrix33ToRowMajorArray(const Matrix33 &m33, Array &a, size_t top=0)
double leg_names_interpolator_ratio
std::string getUseForceModeString()
bool getAutoBalancerParam(OpenHRP::AutoBalancerService::AutoBalancerParam &i_param)
hrp::Matrix33 OrientRotationMatrix(const hrp::Matrix33 &rot, const hrp::Vector3 &axis1, const hrp::Vector3 &axis2)
std::map< std::string, size_t > contact_states_index_map
TimedBooleanSeq m_actContactStates
coil::Properties & getConfig()
OutPort< TimedPoint3D > m_cogOut
std::vector< std::string > sensor_names
void getOutputParametersForWalking()
hrp::Vector3 hand_fix_initial_offset
hrp::JointPathExPtr manip
bool getGaitGeneratorParam(OpenHRP::AutoBalancerService::GaitGeneratorParam &i_param)
void rotm3times(hrp::Matrix33 &m12, const hrp::Matrix33 &m1, const hrp::Matrix33 &m2)
AutoBalancer(RTC::Manager *manager)
unsigned int m_debugLevel
virtual RTC::ReturnCode_t onInitialize()
ExecutionContextHandle_t UniqueId
std::string graspless_manip_arm
interpolator * transition_interpolator
std::vector< hrp::Vector3 > ref_moments
std::map< std::string, hrp::VirtualForceSensorParam > m_vfs
interpolator * leg_names_interpolator
InPort< TimedLong > m_emergencySignalIn
TimedPoint3D m_refFootOriginExtMoment
std::vector< std::string > ee_vec
bool startAutoBalancer(const ::OpenHRP::AutoBalancerService::StrSequence &limbs)
hrp::Vector3 sbp_cog_offset
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
hrp::Vector3 prev_ref_zmp
def j(str, encoding="cp932")
CORBA::Long find(const CorbaSequence &seq, Functor f)
RTC::OutPort< RTC::TimedPoint3D > m_zmpOut
static const char * autobalancer_spec[]
hrp::Vector3 prev_imu_sensor_vel
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
void getTargetParameters()
std::vector< OutPort< TimedDoubleSeq > * > m_ref_forceOut
InPort< TimedPoint3D > m_zmpIn
enum AutoBalancer::@3 control_mode
std::vector< TimedDoubleSeq > m_ref_force
TimedPoint3D m_sbpCogOffset
OutPort< TimedPoint3D > m_basePosOut
AutoBalancerService_impl m_service0
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
TimedAcceleration3D m_accRef
OutPort< TimedAcceleration3D > m_accRefOut
bool getGoPosFootstepsSequence(const double &x, const double &y, const double &th, OpenHRP::AutoBalancerService::FootstepsSequence_out o_footstep)
int calcPseudoInverse(const dmatrix &_a, dmatrix &_a_pseu, double _sv_ratio)
void calcFixCoordsForAdjustFootstep(rats::coordinates &tmp_fix_coords)
TimedDoubleSeq m_optionalData
void getOutputParametersForABC()
TimedBoolean m_walkingStates
OutPort< TimedDoubleSeq > m_qOut
void rotateRefForcesForFixCoords(rats::coordinates &tmp_fix_coords)
HRP_UTIL_EXPORT Vector3 rpyFromRot(const Matrix33 &m)
hrp::Vector3 graspless_manip_p_gain
std::vector< hrp::Vector3 > ref_forces
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
virtual RTC::ReturnCode_t onDeactivated(RTC::UniqueId ec_id)
Vector3 cross(const Vector3 &v1, const Vector3 &v2)
void calcReferenceJointAnglesForIK()
OutPort< TimedPose3D > m_basePoseOut
InPort< TimedBooleanSeq > m_actContactStatesIn
bool goVelocity(const double &vx, const double &vy, const double &vth)
std::vector< OutPort< TimedPoint3D > * > m_limbCOPOffsetOut
InPort< TimedDoubleSeq > m_qRefIn
TimedDoubleSeq m_baseTform
InPort< TimedPoint3D > m_refFootOriginExtMomentIn
void registerInPort(const char *name, InPortBase &inport)
InPort< TimedOrientation3D > m_baseRpyIn
void get(double *x_, bool popp=true)
void fixLegToCoords2(rats::coordinates &tmp_fix_coords)
TimedDoubleSeq m_controlSwingSupportTime
bool addPort(PortBase &port)
virtual bool write(DataType &value)
RTC::CorbaPort m_AutoBalancerServicePort
hrp::Vector3 additional_force_applied_point_offset
rats::coordinates fix_leg_coords
InPort< TimedPoint3D > m_diffCPIn
void distributeReferenceZMPToWrenches(const hrp::Vector3 &_ref_zmp)
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
bool setFootSteps(const OpenHRP::AutoBalancerService::FootstepSequence &fs, CORBA::Long overwrite_fs_idx)
OutPort< TimedOrientation3D > m_baseRpyOut
enum AutoBalancer::@4 use_force
void calcWeightedLinearEquation(hrp::dvector &ret, const hrp::dmatrix &A, const hrp::dmatrix &W, const hrp::dvector &b)
hrp::Matrix33 target_root_R
bool releaseEmergencyStop()
bool getRemainingFootstepSequence(OpenHRP::AutoBalancerService::FootstepSequence_out o_footstep, CORBA::Long &o_current_fs_idx)
std::vector< TimedDoubleSeq > m_force
bool addInPort(const char *name, InPortBase &inport)
interpolator * zmp_offset_interpolator
void static_balance_point_proc_one(hrp::Vector3 &tmp_input_sbp, const double ref_com_height)
void setGoal(const double *gx, const double *gv, double time, bool online=true)
void mid_rot(hrp::Matrix33 &mid_rot, const double p, const hrp::Matrix33 &rot1, const hrp::Matrix33 &rot2, const double eps)
void registerOutPort(const char *name, OutPortBase &outport)
hrp::Vector3 calc_vel_from_hand_error(const rats::coordinates &tmp_fix_coords)
OutPort< TimedBoolean > m_walkingStatesOut
hrp::Matrix33 input_baseRot
double adjust_footstep_transition_time
rats::coordinates graspless_manip_reference_trans_coords
bool isOptionalDataContact(const std::string &ee_name)
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
void waitFootStepsEarly(const double tm)
void calc_static_balance_point_from_forces(hrp::Vector3 &sb_point, const hrp::Vector3 &tmpcog, const double ref_com_height)
bool setGaitGeneratorParam(const OpenHRP::AutoBalancerService::GaitGeneratorParam &i_param)
void startABCparam(const ::OpenHRP::AutoBalancerService::StrSequence &limbs)
hrp::Vector3 input_basePos
coil::Guard< coil::Mutex > Guard
void set(const double *x, const double *v=NULL)
hrp::Vector3 target_root_p
TimedBoolean m_refFootOriginExtMomentIsHoldValue
void mid_coords(coordinates &mid_coords, const double p, const coordinates &c1, const coordinates &c2, const double eps)
bool goPos(const double &x, const double &y, const double &th)
int usleep(useconds_t usec)
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)