File tree Expand file tree Collapse file tree 3 files changed +7
-4
lines changed
bitbots_motion/bitbots_quintic_walk
bitbots_wolfgang/wolfgang_description/urdf Expand file tree Collapse file tree 3 files changed +7
-4
lines changed Original file line number Diff line number Diff line change 1
1
walking :
2
2
ros__parameters :
3
3
engine :
4
- double_support_ratio : 0.05
4
+ double_support_ratio : 0.30
5
5
foot_distance : 0.2
6
6
foot_rise : 0.05
7
7
freq : 0.5
@@ -11,7 +11,7 @@ walking:
11
11
trunk_pitch_p_coef_forward : 0.0
12
12
trunk_pitch_p_coef_turn : 0.0
13
13
trunk_swing : 0.25
14
- trunk_x_offset : 0.0
14
+ trunk_x_offset : -0.05
15
15
trunk_y_offset : 0.005
16
16
trunk_z_movement : 0.0
17
17
first_step_swing_factor : 1.0
Original file line number Diff line number Diff line change @@ -518,6 +518,9 @@ void WalkEngine::buildTrajectories(WalkEngine::TrajectoryType type) {
518
518
foot_spline_.pitch ()->addPoint (0.0 , foot_orientation_pos_at_last_foot_change_.y (),
519
519
foot_orientation_vel_at_last_foot_change_.y (),
520
520
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);
521
524
foot_spline_.pitch ()->addPoint (half_period, 0.0 );
522
525
523
526
foot_spline_.yaw ()->addPoint (0.0 , foot_orientation_pos_at_last_foot_change_.z (),
Original file line number Diff line number Diff line change 1985
1985
</inertial >
1986
1986
</link >
1987
1987
<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" />
1989
1989
<axis xyz =" 0.0 0.0 0.0" />
1990
1990
<parent link =" r_foot" />
1991
1991
<child link =" r_sole" />
3134
3134
</inertial >
3135
3135
</link >
3136
3136
<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" />
3138
3138
<axis xyz =" 0.0 0.0 0.0" />
3139
3139
<parent link =" l_foot" />
3140
3140
<child link =" l_sole" />
You can’t perform that action at this time.
0 commit comments