Skip to content

Commit 9e027aa

Browse files
experimental 5 cm foot pitch rigging offset
1 parent 73662b5 commit 9e027aa

File tree

3 files changed

+7
-4
lines changed

3 files changed

+7
-4
lines changed

bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_viz.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
walking:
22
ros__parameters:
33
engine:
4-
double_support_ratio: 0.05
4+
double_support_ratio: 0.30
55
foot_distance: 0.2
66
foot_rise: 0.05
77
freq: 0.5
@@ -11,7 +11,7 @@ walking:
1111
trunk_pitch_p_coef_forward: 0.0
1212
trunk_pitch_p_coef_turn: 0.0
1313
trunk_swing: 0.25
14-
trunk_x_offset: 0.0
14+
trunk_x_offset: -0.05
1515
trunk_y_offset: 0.005
1616
trunk_z_movement: 0.0
1717
first_step_swing_factor: 1.0

bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -518,6 +518,9 @@ void WalkEngine::buildTrajectories(WalkEngine::TrajectoryType type) {
518518
foot_spline_.pitch()->addPoint(0.0, foot_orientation_pos_at_last_foot_change_.y(),
519519
foot_orientation_vel_at_last_foot_change_.y(),
520520
foot_orientation_acc_at_foot_change_.y());
521+
foot_spline_.pitch()->addPoint(double_support_length, 0.1);
522+
// foot_spline_.pitch()->addPoint(double_support_length, config_.foot_pitch_angle);
523+
// foot_spline_.pitch()->addPoint(double_support_length + single_support_length * config_.foot_apex_phase, 0.1);
521524
foot_spline_.pitch()->addPoint(half_period, 0.0);
522525

523526
foot_spline_.yaw()->addPoint(0.0, foot_orientation_pos_at_last_foot_change_.z(),

bitbots_wolfgang/wolfgang_description/urdf/robot.urdf

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1985,7 +1985,7 @@
19851985
</inertial>
19861986
</link>
19871987
<joint name="r_sole_frame" type="fixed">
1988-
<origin rpy="-4.1858e-16 2.36866e-15 1.5708" xyz="0.0152219 0.0907683 -0.0529"/>
1988+
<origin rpy="-4.1858e-16 2.36866e-15 1.5708" xyz="0.0152219 0.1407683 -0.0529"/>
19891989
<axis xyz="0.0 0.0 0.0"/>
19901990
<parent link="r_foot"/>
19911991
<child link="r_sole"/>
@@ -3134,7 +3134,7 @@
31343134
</inertial>
31353135
</link>
31363136
<joint name="l_sole_frame" type="fixed">
3137-
<origin rpy="-5.77818e-15 -6.98371e-15 1.5708" xyz="-0.0152219 0.0907683 -0.0529"/>
3137+
<origin rpy="-5.77818e-15 -6.98371e-15 1.5708" xyz="-0.0152219 0.1407683 -0.0529"/>
31383138
<axis xyz="0.0 0.0 0.0"/>
31393139
<parent link="l_foot"/>
31403140
<child link="l_sole"/>

0 commit comments

Comments
 (0)