@@ -123,13 +123,14 @@ WalkResponse WalkEngine::update(double dt) {
123
123
engine_state_ = WalkState::PAUSED;
124
124
pause_requested_ = false ;
125
125
return createResponse ();
126
- } else if (half_step_finished &&
126
+ } else if (half_step_finished && positioning_step_to_kick_point_ &&
127
127
((left_kick_requested_ && !is_left_support_foot_) || (right_kick_requested_ && is_left_support_foot_))) {
128
128
// lets do a kick
129
129
buildTrajectories (TrajectoryType::KICK);
130
130
engine_state_ = WalkState::KICK;
131
131
left_kick_requested_ = false ;
132
132
right_kick_requested_ = false ;
133
+ positioning_step_to_kick_point_ = false ;
133
134
} else if (half_step_finished) {
134
135
// current step is finished, lets see if we have to change state
135
136
if (request_.single_step ) {
@@ -395,7 +396,14 @@ void WalkEngine::buildTrajectories(WalkEngine::TrajectoryType type) {
395
396
if (!start_movement) {
396
397
saveCurrentRobotState ();
397
398
if (!stop_step) {
398
- stepFromOrders (request_.linear_orders , request_.angular_z );
399
+ if (left_kick_requested_ or right_kick_requested_) {
400
+ // we are in a kick step, so
401
+ // we need to position ourselves to the kick point
402
+ stepToApproachKick (kick_point_, left_kick_requested_);
403
+ } else {
404
+ // we are in a normal step, the requested translation/rotation is the step
405
+ stepFromOrders (request_.linear_orders , request_.angular_z );
406
+ }
399
407
} else {
400
408
stepFromOrders ({0 , 0 , 0 }, 0 );
401
409
}
@@ -812,12 +820,15 @@ bool WalkEngine::isDoubleSupport() {
812
820
return is_double_support_spline_.pos (getTrajsTime ()) >= 0.5 ;
813
821
}
814
822
815
- void WalkEngine::requestKick (bool left) {
816
- if (left) {
817
- left_kick_requested_ = true ;
823
+ void WalkEngine::requestKick (tf2::Transform kick_point) {
824
+ // We assume that the kick point is given in the support foot frame
825
+ if (is_left_support_foot_) {
826
+ kick_point = left_in_world_ * kick_point;
818
827
} else {
819
- right_kick_requested_ = true ;
828
+ kick_point = right_in_world_ * kick_point ;
820
829
}
830
+
831
+ left_kick_requested_ = true ; // TODO better feet selection
821
832
}
822
833
823
834
void WalkEngine::requestPause () { pause_requested_ = true ; }
@@ -851,10 +862,73 @@ void WalkEngine::stepFromSupport(const tf2::Transform& diff) {
851
862
is_left_support_foot_ = !is_left_support_foot_;
852
863
}
853
864
865
+ void WalkEngine::stepToApproachKick (const tf2::Transform kick_point_and_direction, bool kick_with_left) {
866
+ // Compute where it is relative to the support foot, the kick point and direction are given in "world" / walk odom
867
+ // coordinates
868
+ tf2::Transform kick_point_from_support;
869
+ if (is_left_support_foot_) {
870
+ kick_point_from_support = right_in_world_.inverseTimes (kick_point_and_direction);
871
+ } else {
872
+ kick_point_from_support = left_in_world_.inverseTimes (kick_point_and_direction);
873
+ }
874
+
875
+ double distance_to_kick_point = 0.15 ; // Offset to the kick point, because we don't want to accidentally touch it and
876
+ // our feet have a certain size
877
+ tf2::Transform kick_point_from_support_with_offset = tf2::Transform::getIdentity ();
878
+ kick_point_from_support_with_offset.getOrigin ().setX (-distance_to_kick_point);
879
+
880
+ tf2::Transform kick_foot_placement = kick_point_from_support * kick_point_from_support_with_offset;
881
+
882
+ tf2::Transform foot_goal;
883
+
884
+ if (is_left_support_foot_ == kick_with_left) {
885
+ // We can not place the foot on the kick point, because it is the support foot
886
+ // Therfore we try to place the other foot next to it in an attempt to get as close as possible
887
+ // and place the kick foot in the step after
888
+
889
+ tf2::Transform foot_distance = tf2::Transform::getIdentity ();
890
+ if (is_left_support_foot_) {
891
+ foot_distance.getOrigin ().setY (config_.foot_distance );
892
+ } else {
893
+ foot_distance.getOrigin ().setY (-config_.foot_distance );
894
+ }
895
+ foot_goal = kick_foot_placement * foot_distance;
896
+ RCLCPP_WARN (node_->get_logger (), " Placing the kick foot not possible, placing the other foot next to it" );
897
+ } else {
898
+ // Now we do the step to the kick point (the positioning step)
899
+ positioning_step_to_kick_point_ = true ;
900
+
901
+ RCLCPP_WARN (node_->get_logger (), " Placing the kick foot" );
902
+
903
+ foot_goal = kick_foot_placement;
904
+ }
905
+
906
+ // Allow lateral step only on external foot
907
+ // (internal foot will return to zero pose)
908
+ // We need to subtract a small value from the foot distance, otherwise the claming is triggered which,
909
+ // in turn, delays the kick, as we might not be able to reach the kick point yet
910
+ if ((is_left_support_foot_ && foot_goal.getOrigin ().getY () < config_.foot_distance - 0.01 ) ||
911
+ (!is_left_support_foot_ && foot_goal.getOrigin ().getY () > -config_.foot_distance + 0.01 )) {
912
+ RCLCPP_WARN (node_->get_logger (), " Side step not possible, placing the foot back to zero pose" );
913
+
914
+ if (is_left_support_foot_) {
915
+ foot_goal.getOrigin ().setY (config_.foot_distance );
916
+ } else {
917
+ foot_goal.getOrigin ().setY (-config_.foot_distance );
918
+ }
919
+
920
+ // If we tried to position the foot with this step this is not possible anymore and we need to do a normal step
921
+ positioning_step_to_kick_point_ = false ;
922
+ }
923
+
924
+ // Now we can perform the step
925
+ stepFromSupport (foot_goal);
926
+ }
927
+
854
928
void WalkEngine::stepFromOrders (const std::vector<double >& linear_orders, double angular_z) {
855
929
// Compute step diff in next support foot frame
856
- tf2::Transform tmp_diff = tf2::Transform ();
857
- tmp_diff. setIdentity ();
930
+ tf2::Transform tmp_diff = tf2::Transform::getIdentity ();
931
+
858
932
// No change in forward step and upward step
859
933
tmp_diff.getOrigin ()[0 ] = linear_orders[0 ];
860
934
tmp_diff.getOrigin ()[2 ] = linear_orders[2 ];
0 commit comments