Skip to content

Commit 51a86b7

Browse files
committed
Add foot step based kick approach
1 parent 29f0423 commit 51a86b7

File tree

4 files changed

+113
-13
lines changed

4 files changed

+113
-13
lines changed

bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_engine.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ class WalkEngine : public bitbots_splines::AbstractEngine<WalkRequest, WalkRespo
6666
*/
6767
bool isDoubleSupport();
6868

69-
void requestKick(bool left);
69+
void requestKick(tf2::Transform kick_point);
7070

7171
void requestPause();
7272

@@ -120,6 +120,8 @@ class WalkEngine : public bitbots_splines::AbstractEngine<WalkRequest, WalkRespo
120120
// kick handling
121121
bool left_kick_requested_ = false;
122122
bool right_kick_requested_ = false;
123+
bool positioning_step_to_kick_point_ = false;
124+
tf2::Transform kick_point_ = tf2::Transform::getIdentity();
123125

124126
// Current support foot (left or right).
125127
bool is_left_support_foot_ = false;
@@ -174,6 +176,8 @@ class WalkEngine : public bitbots_splines::AbstractEngine<WalkRequest, WalkRespo
174176
*/
175177
void stepFromSupport(const tf2::Transform &diff);
176178

179+
void stepToApproachKick(const tf2::Transform kick_point_and_direction, bool kick_with_left);
180+
177181
/**
178182
* Set target pose of current support foot using diff orders.
179183
* Zero vector means in place walking.

bitbots_motion/bitbots_quintic_walk/include/bitbots_quintic_walk/walk_node.hpp

+8-2
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,9 @@ The original files can be found at:
1313
#include <tf2/LinearMath/Quaternion.h>
1414
#include <tf2/LinearMath/Transform.h>
1515
#include <tf2/LinearMath/Vector3.h>
16+
#include <tf2_ros/buffer.h>
1617
#include <tf2_ros/transform_broadcaster.h>
18+
#include <tf2_ros/transform_listener.h>
1719
#include <unistd.h>
1820

1921
#include <Eigen/Dense>
@@ -131,7 +133,7 @@ class WalkNode {
131133

132134
void jointStateCb(sensor_msgs::msg::JointState::SharedPtr msg);
133135

134-
void kickCb(std_msgs::msg::Bool::SharedPtr msg);
136+
void kickCb(geometry_msgs::msg::PoseStamped::SharedPtr msg);
135137

136138
double getTimeDelta();
137139

@@ -167,7 +169,7 @@ class WalkNode {
167169
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
168170
rclcpp::Subscription<bitbots_msgs::msg::RobotControlState>::SharedPtr robot_state_sub_;
169171
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
170-
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr kick_sub_;
172+
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr kick_sub_;
171173
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr imu_sub_;
172174
rclcpp::Subscription<bitbots_msgs::msg::FootPressure>::SharedPtr pressure_sub_left_;
173175
rclcpp::Subscription<bitbots_msgs::msg::FootPressure>::SharedPtr pressure_sub_right_;
@@ -177,6 +179,10 @@ class WalkNode {
177179
moveit::core::RobotModelPtr kinematic_model_;
178180
moveit::core::RobotStatePtr current_state_;
179181

182+
// TF listener and buffer
183+
tf2_ros::Buffer tf_buffer_;
184+
tf2_ros::TransformListener tf_listener_;
185+
180186
WalkStabilizer stabilizer_;
181187
WalkIK ik_;
182188
WalkVisualizer visualizer_;

bitbots_motion/bitbots_quintic_walk/src/walk_engine.cpp

+82-8
Original file line numberDiff line numberDiff line change
@@ -123,13 +123,14 @@ WalkResponse WalkEngine::update(double dt) {
123123
engine_state_ = WalkState::PAUSED;
124124
pause_requested_ = false;
125125
return createResponse();
126-
} else if (half_step_finished &&
126+
} else if (half_step_finished && positioning_step_to_kick_point_ &&
127127
((left_kick_requested_ && !is_left_support_foot_) || (right_kick_requested_ && is_left_support_foot_))) {
128128
// lets do a kick
129129
buildTrajectories(TrajectoryType::KICK);
130130
engine_state_ = WalkState::KICK;
131131
left_kick_requested_ = false;
132132
right_kick_requested_ = false;
133+
positioning_step_to_kick_point_ = false;
133134
} else if (half_step_finished) {
134135
// current step is finished, lets see if we have to change state
135136
if (request_.single_step) {
@@ -395,7 +396,14 @@ void WalkEngine::buildTrajectories(WalkEngine::TrajectoryType type) {
395396
if (!start_movement) {
396397
saveCurrentRobotState();
397398
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+
}
399407
} else {
400408
stepFromOrders({0, 0, 0}, 0);
401409
}
@@ -812,12 +820,15 @@ bool WalkEngine::isDoubleSupport() {
812820
return is_double_support_spline_.pos(getTrajsTime()) >= 0.5;
813821
}
814822

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;
818827
} else {
819-
right_kick_requested_ = true;
828+
kick_point = right_in_world_ * kick_point;
820829
}
830+
831+
left_kick_requested_ = true; // TODO better feet selection
821832
}
822833

823834
void WalkEngine::requestPause() { pause_requested_ = true; }
@@ -851,10 +862,73 @@ void WalkEngine::stepFromSupport(const tf2::Transform& diff) {
851862
is_left_support_foot_ = !is_left_support_foot_;
852863
}
853864

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+
854928
void WalkEngine::stepFromOrders(const std::vector<double>& linear_orders, double angular_z) {
855929
// 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+
858932
// No change in forward step and upward step
859933
tmp_diff.getOrigin()[0] = linear_orders[0];
860934
tmp_diff.getOrigin()[2] = linear_orders[2];

bitbots_motion/bitbots_quintic_walk/src/walk_node.cpp

+18-2
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@ WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns,
1515
param_listener_(node_),
1616
config_(param_listener_.get_params()),
1717
walk_engine_(node_, config_.engine),
18+
tf_buffer_(node_->get_clock()),
19+
tf_listener_(tf_buffer_, node),
1820
stabilizer_(node_),
1921
ik_(node_, config_.node.ik),
2022
visualizer_(node_, config_.node.tf) {
@@ -73,7 +75,8 @@ WalkNode::WalkNode(rclcpp::Node::SharedPtr node, const std::string& ns,
7375
"robot_state", 1, std::bind(&WalkNode::robotStateCb, this, _1));
7476
joint_state_sub_ = node_->create_subscription<sensor_msgs::msg::JointState>(
7577
"joint_states", 1, std::bind(&WalkNode::jointStateCb, this, _1));
76-
kick_sub_ = node_->create_subscription<std_msgs::msg::Bool>("kick", 1, std::bind(&WalkNode::kickCb, this, _1));
78+
kick_sub_ =
79+
node_->create_subscription<geometry_msgs::msg::PoseStamped>("kick", 1, std::bind(&WalkNode::kickCb, this, _1));
7780
imu_sub_ = node_->create_subscription<sensor_msgs::msg::Imu>("imu/data", 1, std::bind(&WalkNode::imuCb, this, _1));
7881
pressure_sub_left_ = node_->create_subscription<bitbots_msgs::msg::FootPressure>(
7982
"foot_pressure_left/filtered", 1, std::bind(&WalkNode::pressureLeftCb, this, _1));
@@ -520,7 +523,20 @@ void WalkNode::jointStateCb(const sensor_msgs::msg::JointState::SharedPtr msg) {
520523
}
521524
}
522525

523-
void WalkNode::kickCb(const std_msgs::msg::Bool::SharedPtr msg) { walk_engine_.requestKick(msg->data); }
526+
void WalkNode::kickCb(const geometry_msgs::msg::PoseStamped::SharedPtr msg) {
527+
// Transform the goal pose of the contact point to the support foot frame
528+
std::string support_foot_frame =
529+
walk_engine_.isLeftSupport() ? config_.node.tf.l_sole_frame : config_.node.tf.r_sole_frame;
530+
try {
531+
tf2::Transform transform;
532+
tf2::fromMsg(tf_buffer_.transform(msg, support_foot_frame)->pose, transform);
533+
walk_engine_.requestKick(transform);
534+
} catch (tf2::TransformException& ex) {
535+
RCLCPP_ERROR(node_->get_logger(), "Skipping kick, Could not transform kick goal to support foot frame: %s",
536+
ex.what());
537+
return;
538+
}
539+
}
524540

525541
nav_msgs::msg::Odometry WalkNode::getOdometry() {
526542
// odometry to trunk is transform to support foot * transform from support to trunk

0 commit comments

Comments
 (0)