Skip to content

Commit 2cf7785

Browse files
5 cm toe kinematic offset, as well as new parameter for foot pitch angle
1 parent 9e027aa commit 2cf7785

File tree

4 files changed

+10
-3
lines changed

4 files changed

+10
-3
lines changed

bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_simulator.yaml

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ walking:
1212
kick_vel: 0.2
1313
kick_phase: 0.75
1414

15-
double_support_ratio: 0.0264282002140171
15+
double_support_ratio: 0.264282002140171
1616
first_step_swing_factor: 1.80591386587488
1717
foot_distance: 0.179900277671633
1818
foot_rise: 0.0819786291304007
@@ -30,6 +30,7 @@ walking:
3030
foot_apex_phase: 0.5
3131
foot_overshoot_phase: 1.0
3232
foot_overshoot_ratio: 0.0
33+
foot_pitch_angle: 0.5
3334
foot_put_down_phase: 1.0
3435
foot_z_pause: 0.0
3536
trunk_pause: 0.0

bitbots_motion/bitbots_quintic_walk/config/walking_wolfgang_viz.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@ walking:
1919
foot_apex_phase: 0.5
2020
foot_overshoot_phase: 0.85
2121
foot_overshoot_ratio: 0.1
22+
foot_pitch_angle: 0.5
2223
foot_put_down_phase: 1.0
2324
foot_put_down_z_offset: 0.0
2425
foot_z_pause: 0.0

bitbots_motion/bitbots_quintic_walk/src/parameters.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,11 @@ walking:
9090
description: "Foot X/Y overshoot phase (single support cycle phase, [foot_apex_phase:1])"
9191
validation:
9292
bounds<>: [0.0, 1.0]
93+
foot_pitch_angle:
94+
type: double
95+
description: "Foot pitch angle before toe-off"
96+
validation:
97+
bounds<>: [0.0, 1.0]
9398
trunk_x_offset:
9499
type: double
95100
description: "Trunk X offset (in meters)"

bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -518,8 +518,8 @@ 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);
521+
foot_spline_.pitch()->addPoint(double_support_length, config_.foot_pitch_angle);
522+
// foot_spline_.pitch()->addPoint(double_support_length, 0.1);
523523
// foot_spline_.pitch()->addPoint(double_support_length + single_support_length * config_.foot_apex_phase, 0.1);
524524
foot_spline_.pitch()->addPoint(half_period, 0.0);
525525

0 commit comments

Comments
 (0)