Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tuning icub #108

Open
wants to merge 13 commits into
base: devel
Choose a base branch
from
4 changes: 2 additions & 2 deletions etc/icub/configuration.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<joint name="l_shoulder_pitch" value="-1.02395" />
<joint name="l_shoulder_roll" value="0.511463" />
<joint name="l_shoulder_yaw" value="0.0473993" />
<joint name="l_elbow_joint" value="0.232871" />
<joint name="l_elbow" value="0.232871" />
<joint name="l_wrist_prosup" value="0.0471739" />
<joint name="l_wrist_pitch" value="-0.106723" />
<joint name="l_wrist_yaw" value="0.259116" />
Expand All @@ -30,7 +30,7 @@
<joint name="r_shoulder_pitch" value="-1.02382" />
<joint name="r_shoulder_roll" value="0.511383" />
<joint name="r_shoulder_yaw" value="0.0473731" />
<joint name="r_elbow_joint" value="0.233003" />
<joint name="r_elbow" value="0.233003" />
<joint name="r_wrist_prosup" value="0.0470791" />
<joint name="r_wrist_pitch" value="-0.106679" />
<joint name="r_wrist_yaw" value="0.25915" />
Expand Down
83 changes: 33 additions & 50 deletions etc/icub/configurations.srdf
Original file line number Diff line number Diff line change
@@ -1,55 +1,38 @@
<?xml version="1.0" ?>
<robot name="robot">
<group_state name="inria_start" group="all">
<joint name="root_joint" value=" -0.0522203 0.000467603 0.43 0.0001534 0.0526897 -0.000532457 0.998611" />
<joint name="l_hip_pitch" value="0.589391" />
<joint name="r_hip_pitch" value="0.589391" />

<joint name="l_hip_roll" value="0.0969721" />
<joint name="r_hip_roll" value="0.0969721" />

<joint name="l_hip_yaw" value="-0.0496379" />
<joint name="r_hip_yaw" value="-0.0496379" />

<joint name="l_knee" value="-0.873709" />
<joint name="r_knee" value="-0.873709" />

<joint name="l_ankle_pitch" value="-0.392096" />
<joint name="r_ankle_pitch" value="-0.392096" />

<joint name="l_ankle_roll" value="-0.109139" />
<joint name="r_ankle_roll" value="-0.109139" />



<joint name="torso_pitch" value="0.00670584" />
<joint name="torso_roll" value="-0.000253351" />
<joint name="torso_yaw" value="-0.00176508" />

<joint name="l_shoulder_pitch" value="-1.145" />
<joint name="r_shoulder_pitch" value="-1.145" />

<joint name="l_shoulder_roll" value="0.523578" />
<joint name="r_shoulder_roll" value="0.523578" />

<joint name="l_shoulder_yaw" value="0.0647369" />
<joint name="r_shoulder_yaw" value="0.0647369" />

<joint name="l_elbow_joint" value="0.230685" />
<joint name="r_elbow_joint" value="0.230685" />

<joint name="l_wrist_prosup" value="0.0504902" />
<joint name="r_wrist_prosup" value="0.0504902" />

<joint name="l_wrist_pitch" value="-0.105206" />
<joint name="r_wrist_pitch" value="-0.105206" />

<joint name="l_wrist_yaw" value="0.238379" />
<joint name="r_wrist_yaw" value="0.238379" />

<joint name="neck_pitch" value="0.112923" />
<joint name="neck_roll" value="-0.000713353" />
<joint name="neck_yaw" value="-0.000643952" />

<joint name="root_joint" value="-0.0165507 0.00110185 0.436005 0.00143734 -0.144318 -0.00332486 0.989525" />
<joint name="l_hip_pitch" value="0.0765931" />
<joint name="l_hip_roll" value="0.0957478" />
<joint name="l_hip_yaw" value="0.0" />
<joint name="l_knee" value="-0.817699" />
<joint name="l_ankle_pitch" value="-0.452669" />
<joint name="l_ankle_roll" value="-0.0980072" />
<joint name="r_hip_pitch" value="0.0765931" />
<joint name="r_hip_roll" value="0.0957478" />
<joint name="r_hip_yaw" value="0.0" />
<joint name="r_knee" value="-0.817699" />
<joint name="r_ankle_pitch" value="-0.452669" />
<joint name="r_ankle_roll" value="-0.0980072" />
<joint name="torso_pitch" value="0.3951" />
<joint name="torso_roll" value="0.0" />
<joint name="torso_yaw" value="0.0" />
<joint name="l_shoulder_pitch" value="-0.0619188" />
<joint name="l_shoulder_roll" value="0.377713" />
<joint name="l_shoulder_yaw" value="0.280484" />
<joint name="l_elbow" value="0.838804" />
<joint name="l_wrist_prosup" value="-0.174619" />
<joint name="l_wrist_pitch" value="-0.080911" />
<joint name="l_wrist_yaw" value="-0.0313247" />
<joint name="neck_pitch" value="0." />
<joint name="neck_roll" value="0." />
<joint name="neck_yaw" value="0." />
<joint name="r_shoulder_pitch" value="-0.0619188" />
<joint name="r_shoulder_roll" value="0.377713" />
<joint name="r_shoulder_yaw" value="0.280484" />
<joint name="r_elbow" value="0.838804" />
<joint name="r_wrist_prosup" value="-0.174619" />
<joint name="r_wrist_pitch" value="-0.080911" />
<joint name="r_wrist_yaw" value="-0.0313247" />
</group_state>
</robot>
2 changes: 1 addition & 1 deletion etc/icub/squat.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
BEHAVIOR:
name: humanoid::move_com
trajectory_duration: 1.0
targets: [[0, 0, -0.1]]
targets: [[0, 0, -0.15]]
mask: 001
absolute: false
loop: true
94 changes: 47 additions & 47 deletions etc/icub/tasks.yaml
Original file line number Diff line number Diff line change
@@ -1,57 +1,57 @@
lh:
type: se3
tracked: l_hand
weight: 1.0
kp: 30.0
weight: 150.0
kp: 50.0
mask: 111111 # xyz
rh:
type: se3
tracked: r_hand
weight: 1.0
kp: 30.0
weight: 150.0
kp: 50.0
mask: 111111
lf:
type: se3
tracked: left_foot
tracked: l_foot
weight: 1000.0
kp: 30.0
mask: 111111
rf:
type: se3
tracked: right_foot
weight: 10.0
tracked: r_foot
weight: 1000.0
kp: 30.0
mask: 111111
com:
type: com
weight: 3000.0
kp: 50.0
weight: 10000.0
kp: 250.0
mask: 111
momentum: #!!!!!WARNING IS DISZBLED FOR SINGLE SUPPORT cf parse_stabiliser !!!!!!!!!!!
momentum: #!!!!!WARNING IS DISABLED FOR SINGLE SUPPORT cf parse_stabiliser !!!!!!!!!!!
type: momentum
weight: 1000.0
kp: 30.0
mask: 000110
posture:
type: posture
weight: 0.05
weight: 0.75
kp: 10.0
ref: inria_start
torso:
type: se3
tracked: chest
weight: 1.0
weight: 100.0
kp: 30.0
mask: 000111
mask: 110111
head:
type: se3
tracked: head
weight: 10.0
kp: 30.0
kp: 20.0
mask: 110111
bounds:
type: bounds
weight: 1000.0
weight: 5000.0
contact_lfoot:
type: contact
joint: l_ankle_roll
Expand All @@ -78,35 +78,35 @@ contact_rfoot:
fmax: 1500.0
mu: 0.3
normal: [0, 0, -1]
self_collision-left:
type: self-collision
tracked: l_wrist_yaw
radius: 0.05
avoided:
r_wrist_yaw: 0.05
v_leg_right: 0.08
v_leg_left: 0.08
torso_pitch: 0.11
l_hip_pitch: 0.08
r_hip_pitch: 0.08
l_knee: 0.08
r_knee: 0.08
weight: 500
kp: 700.0
p: 3
self_collision-right:
type: self-collision
tracked: r_wrist_yaw
radius: 0.05
avoided:
l_wrist_yaw: 0.05
v_leg_right: 0.08
v_leg_left: 0.08
torso_pitch: 0.11
l_hip_pitch: 0.08
r_hip_pitch: 0.08
l_knee: 0.08
r_knee: 0.08
weight: 500
kp: 700.0
p: 3
# self_collision-left:
# type: self-collision
# tracked: l_wrist_yaw
# radius: 0.05
# avoided:
# r_wrist_yaw: 0.05
# v_leg_right: 0.08
# v_leg_left: 0.08
# torso_pitch: 0.11
# l_hip_pitch: 0.08
# r_hip_pitch: 0.08
# l_knee: 0.08
# r_knee: 0.08
# weight: 500
# kp: 700.0
# p: 3
# self_collision-right:
# type: self-collision
# tracked: r_wrist_yaw
# radius: 0.05
# avoided:
# l_wrist_yaw: 0.05
# v_leg_right: 0.08
# v_leg_left: 0.08
# torso_pitch: 0.11
# l_hip_pitch: 0.08
# r_hip_pitch: 0.08
# l_knee: 0.08
# r_knee: 0.08
# weight: 500
# kp: 700.0
# p: 3
2 changes: 1 addition & 1 deletion src/controllers/pos_tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ namespace inria_wbc {

//q_tsid_ for talos is of size 37 (pos+quat+nactuated)
auto ref_map = robot_->model().referenceConfigurations;
IWBC_ASSERT(ref_map.find(ref_config) != ref_map.end(), "The following reference config is not in ref_map : ", ref_config);
IWBC_ASSERT(ref_map.find(ref_config) != ref_map.end(), "The following reference config is not in ref_map : ", ref_config, ",from file : ", p_srdf);
q_tsid_ = ref_map[ref_config];

if (floating_base_) {
Expand Down