Skip to content

Commit

Permalink
(AutoBalancer, GaitGenerator, Stabilizer, sample) : Fix end effector …
Browse files Browse the repository at this point in the history
…name, e.g., :rarm => rarm. This change is based on JointGroup name discussed in fkanehiro#232
  • Loading branch information
snozawa committed Aug 14, 2014
1 parent d2f6cb9 commit 29bfe86
Show file tree
Hide file tree
Showing 7 changed files with 80 additions and 80 deletions.
56 changes: 28 additions & 28 deletions rtc/AutoBalancer/AutoBalancer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ RTC::ReturnCode_t AutoBalancer::onInitialize()
fix_leg_coords = coordinates();

// setting from conf file
// :rleg,TARGET_LINK,BASE_LINK
// rleg,TARGET_LINK,BASE_LINK
coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
size_t prop_num = 10;
if (end_effectors_str.size() > 0) {
Expand Down Expand Up @@ -224,7 +224,7 @@ RTC::ReturnCode_t AutoBalancer::onInitialize()
//use_force = MODE_NO_FORCE;
use_force = MODE_REF_FORCE;

if (ikp.find(":rleg") != ikp.end() && ikp.find(":lleg") != ikp.end()) {
if (ikp.find("rleg") != ikp.end() && ikp.find("lleg") != ikp.end()) {
is_legged_robot = true;
} else {
is_legged_robot = false;
Expand Down Expand Up @@ -298,7 +298,7 @@ RTC::ReturnCode_t AutoBalancer::onExecute(RTC::UniqueId ec_id)
solveLimbIK();
} else {
for ( std::map<std::string, ABCIKparam>::iterator it = ikp.begin(); it != ikp.end(); it++ ) {
if (it->first == ":rleg" || it->first == ":lleg") {
if (it->first == "rleg" || it->first == "lleg") {
it->second.current_p0 = m_robot->link(it->second.target_name)->p;
it->second.current_r0 = m_robot->link(it->second.target_name)->R;
}
Expand Down Expand Up @@ -429,16 +429,16 @@ void AutoBalancer::getTargetParameters()
// TODO : assume biped
switch (gg->get_current_support_state()) {
case 0:
m_contactStates.data[contact_states_index_map[":rleg"]] = true;
m_contactStates.data[contact_states_index_map[":lleg"]] = true;
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
break;
case 1:
m_contactStates.data[contact_states_index_map[":rleg"]] = true;
m_contactStates.data[contact_states_index_map[":lleg"]] = false;
m_contactStates.data[contact_states_index_map["rleg"]] = true;
m_contactStates.data[contact_states_index_map["lleg"]] = false;
break;
case 2:
m_contactStates.data[contact_states_index_map[":rleg"]] = false;
m_contactStates.data[contact_states_index_map[":lleg"]] = true;
m_contactStates.data[contact_states_index_map["rleg"]] = false;
m_contactStates.data[contact_states_index_map["lleg"]] = true;
break;
default:
break;
Expand All @@ -462,10 +462,10 @@ void AutoBalancer::getTargetParameters()
it->second.target_r0 = m_robot->link(it->second.target_name)->R;
}
}
ikp[":rleg"].getRobotEndCoords(rc, m_robot);
ikp[":lleg"].getRobotEndCoords(lc, m_robot);
rc.translate(default_zmp_offsets[0]); /* :rleg */
lc.translate(default_zmp_offsets[1]); /* :lleg */
ikp["rleg"].getRobotEndCoords(rc, m_robot);
ikp["lleg"].getRobotEndCoords(lc, m_robot);
rc.translate(default_zmp_offsets[0]); /* rleg */
lc.translate(default_zmp_offsets[1]); /* lleg */
if (gg_is_walking) {
ref_cog = gg->get_cog();
} else {
Expand Down Expand Up @@ -496,8 +496,8 @@ void AutoBalancer::fixLegToCoords (const std::string& leg, const coordinates& co
{
coordinates tar, ref, delta, tmp;
coordinates rleg_endcoords, lleg_endcoords;
ikp[":rleg"].getRobotEndCoords(rleg_endcoords, m_robot);
ikp[":lleg"].getRobotEndCoords(lleg_endcoords, m_robot);
ikp["rleg"].getRobotEndCoords(rleg_endcoords, m_robot);
ikp["lleg"].getRobotEndCoords(lleg_endcoords, m_robot);
mid_coords(tar, 0.5, rleg_endcoords , lleg_endcoords);
tmp = coords;
ref = coordinates(m_robot->rootLink()->p, m_robot->rootLink()->R);
Expand Down Expand Up @@ -627,13 +627,13 @@ void AutoBalancer::startWalking ()
return_control_mode = control_mode;
OpenHRP::AutoBalancerService::StrSequence fix_limbs;
fix_limbs.length(2);
fix_limbs[0] = ":rleg";
fix_limbs[1] = ":lleg";
fix_limbs[0] = "rleg";
fix_limbs[1] = "lleg";
startABCparam(fix_limbs);
waitABCTransition();
}
hrp::Vector3 cog(m_robot->calcCM());
std::string init_support_leg (gg->get_footstep_front_leg() == ":rleg" ? ":lleg" : ":rleg");
std::string init_support_leg (gg->get_footstep_front_leg() == "rleg" ? "lleg" : "rleg");
std::string init_swing_leg (gg->get_footstep_front_leg());
coordinates spc, swc;
gg->set_default_zmp_offsets(default_zmp_offsets);
Expand All @@ -653,8 +653,8 @@ void AutoBalancer::stopWalking ()
} else {
/* overwrite sequencer's angle-vector when finishing steps */
coordinates rleg_endcoords, lleg_endcoords;
ikp[":rleg"].getTargetEndCoords(rleg_endcoords);
ikp[":lleg"].getTargetEndCoords(lleg_endcoords);
ikp["rleg"].getTargetEndCoords(rleg_endcoords);
ikp["lleg"].getTargetEndCoords(lleg_endcoords);
mid_coords(fix_leg_coords, 0.5, rleg_endcoords, lleg_endcoords);
fixLegToCoords(":both", fix_leg_coords);
gg->clear_footstep_node_list();
Expand Down Expand Up @@ -696,8 +696,8 @@ bool AutoBalancer::goPos(const double& x, const double& y, const double& th)
{
coordinates foot_midcoords;
coordinates rleg_endcoords, lleg_endcoords;
ikp[":rleg"].getTargetEndCoords(rleg_endcoords);
ikp[":lleg"].getTargetEndCoords(lleg_endcoords);
ikp["rleg"].getTargetEndCoords(rleg_endcoords);
ikp["lleg"].getTargetEndCoords(lleg_endcoords);
mid_coords(foot_midcoords, 0.5, rleg_endcoords, lleg_endcoords);
gg->go_pos_param_2_footstep_list(x, y, th, foot_midcoords);
gg->print_footstep_list();
Expand All @@ -712,8 +712,8 @@ bool AutoBalancer::goVelocity(const double& vx, const double& vy, const double&
} else {
coordinates foot_midcoords;
coordinates rleg_endcoords, lleg_endcoords;
ikp[":rleg"].getTargetEndCoords(rleg_endcoords);
ikp[":lleg"].getTargetEndCoords(lleg_endcoords);
ikp["rleg"].getTargetEndCoords(rleg_endcoords);
ikp["lleg"].getTargetEndCoords(lleg_endcoords);
mid_coords(foot_midcoords, 0.5, rleg_endcoords, lleg_endcoords);
gg->initialize_velocity_mode(foot_midcoords, vx, vy, vth);
startWalking();
Expand All @@ -739,7 +739,7 @@ bool AutoBalancer::setFootSteps(const OpenHRP::AutoBalancerService::FootstepSequ
gg->clear_footstep_node_list();
for (size_t i = 0; i < fs.length(); i++) {
std::string leg(fs[i].leg);
if (leg == ":rleg" || leg == ":lleg") {
if (leg == "rleg" || leg == "lleg") {
memcpy(tmpfs.pos.data(), fs[i].pos, sizeof(double)*3);
tmpfs.rot = (Eigen::Quaternion<double>(fs[i].rot[0], fs[i].rot[1], fs[i].rot[2], fs[i].rot[3])).normalized().toRotationMatrix(); // rtc: (x, y, z, w) but eigen: (w, x, y, z)
initial_input_coords.transformation(fstrans, tmpfs);
Expand Down Expand Up @@ -836,16 +836,16 @@ void AutoBalancer::copyRatscoords2Footstep(OpenHRP::AutoBalancerService::Footste
bool AutoBalancer::getFootstepParam(OpenHRP::AutoBalancerService::FootstepParam& i_param)
{
coordinates rleg_endcoords, lleg_endcoords;
ikp[":rleg"].getCurrentEndCoords(rleg_endcoords);
ikp[":lleg"].getCurrentEndCoords(lleg_endcoords);
ikp["rleg"].getCurrentEndCoords(rleg_endcoords);
ikp["lleg"].getCurrentEndCoords(lleg_endcoords);
copyRatscoords2Footstep(i_param.rleg_coords, rleg_endcoords);
copyRatscoords2Footstep(i_param.lleg_coords, lleg_endcoords);
copyRatscoords2Footstep(i_param.support_leg_coords, gg->get_support_leg_coords());
copyRatscoords2Footstep(i_param.swing_leg_coords, gg->get_swing_leg_coords());
copyRatscoords2Footstep(i_param.swing_leg_src_coords, gg->get_swing_leg_src_coords());
copyRatscoords2Footstep(i_param.swing_leg_dst_coords, gg->get_swing_leg_dst_coords());
copyRatscoords2Footstep(i_param.dst_foot_midcoords, gg->get_dst_foot_midcoords());
if (gg->get_support_leg() == ":rleg") {
if (gg->get_support_leg() == "rleg") {
i_param.support_leg = OpenHRP::AutoBalancerService::RLEG;
} else {
i_param.support_leg = OpenHRP::AutoBalancerService::LLEG;
Expand Down
2 changes: 1 addition & 1 deletion rtc/AutoBalancer/GaitGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,7 +280,7 @@ namespace rats
const std::string& tmp_swing_leg,
const coordinates& _support_leg_coords)
{
leg_type _swing_leg = (tmp_swing_leg == ":rleg") ? WC_RLEG : WC_LLEG;
leg_type _swing_leg = (tmp_swing_leg == "rleg") ? WC_RLEG : WC_LLEG;
step_node sn0((_swing_leg == WC_RLEG) ? WC_LLEG : WC_RLEG, _support_leg_coords);
footstep_node_list.push_back(sn0);
step_node sn1(_swing_leg, _support_leg_coords);
Expand Down
16 changes: 8 additions & 8 deletions rtc/AutoBalancer/GaitGenerator.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ namespace rats
step_node (const leg_type _l_r, const coordinates& _worldcoords)
: l_r(_l_r), worldcoords(_worldcoords) {};
step_node (const std::string& _l_r, const coordinates& _worldcoords)
: l_r((_l_r == ":rleg") ? WC_RLEG : WC_LLEG), worldcoords(_worldcoords) {};
: l_r((_l_r == "rleg") ? WC_RLEG : WC_LLEG), worldcoords(_worldcoords) {};
void print_eus_footstep (std::ostream& strm, const bool use_newline = true) const
{
strm << "(cons " << (l_r == WC_RLEG ? ":rleg " : ":lleg ");
strm << "(cons " << (l_r == WC_RLEG ? "rleg " : "lleg ");
worldcoords.print_eus_coordinates(strm, false);
strm << ")";
if (use_newline) strm << std::endl;
Expand Down Expand Up @@ -73,7 +73,7 @@ namespace rats
public:
#endif
std::vector<hrp::Vector3> refzmp_cur_list;
std::vector<hrp::Vector3> default_zmp_offsets; /* (list :rleg :lleg) */
std::vector<hrp::Vector3> default_zmp_offsets; /* (list rleg lleg) */
size_t fs_index, refzmp_index, refzmp_count;
void calc_current_refzmp (hrp::Vector3& ret, const double default_double_support_ratio, const size_t one_step_len) const;
#ifndef HAVE_MAIN
Expand Down Expand Up @@ -328,7 +328,7 @@ namespace rats
bool proc_one_tick ();
void append_footstep_node (const std::string& _leg, const coordinates& _fs)
{
footstep_node_list.push_back(step_node((_leg == ":rleg") ? WC_RLEG : WC_LLEG, _fs));
footstep_node_list.push_back(step_node((_leg == "rleg") ? WC_RLEG : WC_LLEG, _fs));
};
void clear_footstep_node_list () { footstep_node_list.clear(); };
void go_pos_param_2_footstep_list (const double goal_x, const double goal_y, const double goal_theta, /* [mm] [mm] [deg] */
Expand Down Expand Up @@ -385,10 +385,10 @@ namespace rats
/* parameter getting */
const hrp::Vector3& get_cog () { return cog; };
const hrp::Vector3& get_refzmp () { return refzmp;};
const std::string get_footstep_front_leg () const { return footstep_node_list[0].l_r == WC_RLEG ? ":rleg" : ":lleg"; };
const std::string get_footstep_back_leg () const { return footstep_node_list.back().l_r == WC_RLEG ? ":rleg" : ":lleg"; };
const std::string get_support_leg() const { return lcg.get_support_leg() == WC_RLEG ? ":rleg" : ":lleg";};
const std::string get_swing_leg() const { return lcg.get_support_leg() == WC_RLEG ? ":lleg" : ":rleg";};
const std::string get_footstep_front_leg () const { return footstep_node_list[0].l_r == WC_RLEG ? "rleg" : "lleg"; };
const std::string get_footstep_back_leg () const { return footstep_node_list.back().l_r == WC_RLEG ? "rleg" : "lleg"; };
const std::string get_support_leg() const { return lcg.get_support_leg() == WC_RLEG ? "rleg" : "lleg";};
const std::string get_swing_leg() const { return lcg.get_support_leg() == WC_RLEG ? "lleg" : "rleg";};
const coordinates& get_swing_leg_coords() const { return lcg.get_swing_leg_coords(); };
const coordinates& get_support_leg_coords() const { return lcg.get_support_leg_coords(); };
const coordinates& get_swing_leg_src_coords() const { return lcg.get_swing_leg_src_coords(); };
Expand Down
52 changes: 26 additions & 26 deletions rtc/AutoBalancer/testGaitGenerator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@ void test0 ()
{
double dt = 0.005; /* [s] */
std::vector<hrp::Vector3> leg_pos; /* default footstep transformations are necessary */
leg_pos.push_back(hrp::Vector3(0,1e-3*-105,0)); /* :rleg */
leg_pos.push_back(hrp::Vector3(0,1e-3* 105,0)); /* :lleg */
leg_pos.push_back(hrp::Vector3(0,1e-3*-105,0)); /* rleg */
leg_pos.push_back(hrp::Vector3(0,1e-3* 105,0)); /* lleg */
gait_generator gg(dt, leg_pos, 1e-3*150, 1e-3*50, 10);

/* this is c++ version example of test3, test6, test7 and test8 in euslib/demo/nozawa/motion/test-gait-generator.l */
Expand Down Expand Up @@ -48,14 +48,14 @@ void test0 ()
// coordinates initial_support_leg_coords(hrp::Vector3(0, 105, 0)), initial_swing_leg_dst_coords(hrp::Vector3(0, -105, 0));
// /* initialize sample footstep_list */
// gg.clear_footstep_node_list();
// gg.append_footstep_node(":rleg", initial_swing_leg_dst_coords);
// gg.append_footstep_node(":lleg", initial_support_leg_coords);
// gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(50, -105, 0)));
// gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(100, 105, 0)));
// gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(150, -105, 0)));
// gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(200, 105, 0)));
// gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(250, -105, 0)));
// gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(250, 105, 0)));
// gg.append_footstep_node("rleg", initial_swing_leg_dst_coords);
// gg.append_footstep_node("lleg", initial_support_leg_coords);
// gg.append_footstep_node("rleg", coordinates(hrp::Vector3(50, -105, 0)));
// gg.append_footstep_node("lleg", coordinates(hrp::Vector3(100, 105, 0)));
// gg.append_footstep_node("rleg", coordinates(hrp::Vector3(150, -105, 0)));
// gg.append_footstep_node("lleg", coordinates(hrp::Vector3(200, 105, 0)));
// gg.append_footstep_node("rleg", coordinates(hrp::Vector3(250, -105, 0)));
// gg.append_footstep_node("lleg", coordinates(hrp::Vector3(250, 105, 0)));
// gg.initialize_gait_parameter(cog, initial_support_leg_coords, initial_swing_leg_dst_coords);
// while ( !gg.proc_one_tick() );
// gg.print_footstep_list();
Expand Down Expand Up @@ -114,14 +114,14 @@ void test0 ()
coordinates initial_support_leg_coords(hrp::Vector3(0, 1e-3*105, 0)), initial_swing_leg_dst_coords(hrp::Vector3(0, 1e-3*-105, 0));
/* initialize sample footstep_list */
gg.clear_footstep_node_list();
gg.append_footstep_node(":rleg", initial_swing_leg_dst_coords);
gg.append_footstep_node(":lleg", initial_support_leg_coords);
gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(50*1e-3, -105*1e-3, 0)));
gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(100*1e-3, 105*1e-3, 0)));
gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(150*1e-3, -105*1e-3, 0)));
gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(200*1e-3, 105*1e-3, 0)));
gg.append_footstep_node(":rleg", coordinates(hrp::Vector3(250*1e-3, -105*1e-3, 0)));
gg.append_footstep_node(":lleg", coordinates(hrp::Vector3(250*1e-3, 105*1e-3, 0)));
gg.append_footstep_node("rleg", initial_swing_leg_dst_coords);
gg.append_footstep_node("lleg", initial_support_leg_coords);
gg.append_footstep_node("rleg", coordinates(hrp::Vector3(50*1e-3, -105*1e-3, 0)));
gg.append_footstep_node("lleg", coordinates(hrp::Vector3(100*1e-3, 105*1e-3, 0)));
gg.append_footstep_node("rleg", coordinates(hrp::Vector3(150*1e-3, -105*1e-3, 0)));
gg.append_footstep_node("lleg", coordinates(hrp::Vector3(200*1e-3, 105*1e-3, 0)));
gg.append_footstep_node("rleg", coordinates(hrp::Vector3(250*1e-3, -105*1e-3, 0)));
gg.append_footstep_node("lleg", coordinates(hrp::Vector3(250*1e-3, 105*1e-3, 0)));
gg.initialize_gait_parameter(cog, initial_support_leg_coords, initial_swing_leg_dst_coords);
while ( !gg.proc_one_tick() );
gg.print_footstep_list();
Expand Down Expand Up @@ -176,13 +176,13 @@ void test0 ()
// rb->fix_leg_to_coords(":both", coordinates());
// double dt = 0.005; /* [s] */
// std::vector<hrp::Vector3> leg_pos; /* default footstep transformations are necessary */
// leg_pos.push_back(rb->get_end_coords(":rleg").pos); /* :rleg */
// leg_pos.push_back(rb->get_end_coords(":lleg").pos); /* :lleg */
// leg_pos.push_back(rb->get_end_coords("rleg").pos); /* rleg */
// leg_pos.push_back(rb->get_end_coords("lleg").pos); /* lleg */
// gait_generator gg(dt, leg_pos, stride_x, stride_y, stride_th); // for HRP2
// if ( start_leg == "" ) {
// gg.go_pos_param_2_footstep_list(xx, yy, th, coordinates());
// } else {
// gg.go_pos_param_2_footstep_list(xx, yy, th, coordinates(), (start_leg == ":rleg" ? gait_generator::WC_RLEG : gait_generator::WC_LLEG));
// gg.go_pos_param_2_footstep_list(xx, yy, th, coordinates(), (start_leg == "rleg" ? gait_generator::WC_RLEG : gait_generator::WC_LLEG));
// }
// gg.print_footstep_list();
// }
Expand All @@ -194,14 +194,14 @@ void test0 ()
// rb->fix_leg_to_coords(":both", coordinates());
// double dt = 0.005; /* [s] */
// std::vector<hrp::Vector3> leg_pos; /* default footstep transformations are necessary */
// leg_pos.push_back(rb->get_end_coords(":rleg").pos); /* :rleg */
// leg_pos.push_back(rb->get_end_coords(":lleg").pos); /* :lleg */
// leg_pos.push_back(rb->get_end_coords("rleg").pos); /* rleg */
// leg_pos.push_back(rb->get_end_coords("lleg").pos); /* lleg */
// gait_generator gg(dt, leg_pos, 150, 50, 10); // for HRP2
// coordinates spc, swc;
// std::string leg = ":rleg";
// std::string leg = "rleg";
// double goal_x = 0.15, goal_y = 0, goal_z = 0, goal_theta = 0;
// rb->get_end_coords(spc, (leg == ":rleg") ? ":lleg" : ":rleg");
// rb->get_end_coords(swc, (leg == ":rleg") ? ":rleg" : ":lleg");
// rb->get_end_coords(spc, (leg == "rleg") ? "lleg" : "rleg");
// rb->get_end_coords(swc, (leg == "rleg") ? "rleg" : "lleg");
// gg.clear_footstep_node_list();
// gg.go_single_step_param_2_footstep_list(goal_x * 1000.0, goal_y * 1000.0, goal_z * 1000.0, goal_theta,
// leg, spc);
Expand Down
8 changes: 4 additions & 4 deletions rtc/Stabilizer/Stabilizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ RTC::ReturnCode_t Stabilizer::onInitialize()
}

// setting from conf file
// :rleg,TARGET_LINK,BASE_LINK,x,y,z,rx,ry,rz,rth #<=pos + rot (axis+angle)
// rleg,TARGET_LINK,BASE_LINK,x,y,z,rx,ry,rz,rth #<=pos + rot (axis+angle)
coil::vstring end_effectors_str = coil::split(prop["end_effectors"], ",");
if (end_effectors_str.size() > 0) {
size_t prop_num = 10;
Expand Down Expand Up @@ -558,12 +558,12 @@ void Stabilizer::calcFootOriginCoords (hrp::Vector3& foot_origin_pos, hrp::Matri
xv2.normalize();
leg_c[i].rot = OrientRotationMatrix(leg_c[i].rot, xv1, xv2);
}
if (contact_states[contact_states_index_map[":rleg"]] &&
contact_states[contact_states_index_map[":lleg"]]) {
if (contact_states[contact_states_index_map["rleg"]] &&
contact_states[contact_states_index_map["lleg"]]) {
rats::mid_coords(tmpc, 0.5, leg_c[0], leg_c[1]);
foot_origin_pos = tmpc.pos;
foot_origin_rot = tmpc.rot;
} else if (contact_states[contact_states_index_map[":rleg"]]) {
} else if (contact_states[contact_states_index_map["rleg"]]) {
foot_origin_pos = leg_c[0].pos;
foot_origin_rot = leg_c[0].rot;
} else {
Expand Down
2 changes: 1 addition & 1 deletion sample/SampleRobot/SampleRobot.conf.in
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,6 @@ dt: @CONTROLLER_TIME@

abc_leg_offset: 0,0.09,0
abc_stride_parameter: 0.15,0.05,10
end_effectors: :rarm,RARM_WRIST_P,CHEST,0.0,-5.684342e-17,-0.12,9.813078e-18,1.0,0.0,1.5708, :larm,LARM_WRIST_P,CHEST,0.0,5.684342e-17,-0.12,-9.813078e-18,1.0,0.0,1.5708, :rleg,RLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0, :lleg,LLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0,
end_effectors: rarm,RARM_WRIST_P,CHEST,0.0,0,-0.12,0,1.0,0.0,1.5708, larm,LARM_WRIST_P,CHEST,0.0,0,-0.12,0,1.0,0.0,1.5708, rleg,RLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0, lleg,LLEG_ANKLE_R,WAIST,0.0,0.0,-0.07,0.0,0.0,0.0,0.0,

pdgains_sim.file_name: @CMAKE_INSTALL_PREFIX@/share/hrpsys/samples/SampleRobot/SampleRobot.PDgain.dat
Loading

0 comments on commit 29bfe86

Please sign in to comment.