Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

KickState::CHASE_BALLではボール回避をON / KickState::POSITIVE_REDIRECT #606

Merged
merged 6 commits into from
Oct 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
50 changes: 50 additions & 0 deletions crane_robot_skills/include/crane_robot_skills/kick.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ enum class KickState {
AROUND_BALL,
KICK,
REDIRECT_KICK,
POSITIVE_REDIRECT_KICK,
};

class Kick : public SkillBaseWithState<KickState, RobotCommandWrapperPosition>
Expand Down Expand Up @@ -58,6 +59,7 @@ class Kick : public SkillBaseWithState<KickState, RobotCommandWrapperPosition>
visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::ENTRY_POINT");
return Status::RUNNING;
});

addTransition(KickState::ENTRY_POINT, KickState::CHASE_BALL, [this]() {
return world_model()->ball.isMoving(getParameter<double>("moving_speed_threshold"));
});
Expand All @@ -81,20 +83,68 @@ class Kick : public SkillBaseWithState<KickState, RobotCommandWrapperPosition>
command.setTargetPosition(ball_exit_point).lookAtBallFrom(ball_exit_point);
state << "ball_exit: " << ball_exit_point.x() << ", " << ball_exit_point.y();
}
command.enableBallAvoidance();
visualizer->addPoint(robot()->pose.pos, 0, "", 1., state.str());
return Status::RUNNING;
});

addTransition(KickState::CHASE_BALL, KickState::AROUND_BALL, [this]() {
// ボールが止まったら回り込みへ
command.disableBallAvoidance();
return not world_model()->ball.isMoving(getParameter<double>("moving_speed_threshold"));
});

addTransition(KickState::CHASE_BALL, KickState::REDIRECT_KICK, [this]() {
// ボールライン上に乗ったらリダイレクトキックへ
command.disableBallAvoidance();
return world_model()->ball.isMovingTowards(robot()->pose.pos, 10.0) &&
getAngleDiff(
getAngle(world_model()->ball.vel),
getAngle(getParameter<Point>("target") - robot()->pose.pos) < M_PI / 2.0);
});

addTransition(KickState::CHASE_BALL, KickState::POSITIVE_REDIRECT_KICK, [this]() {
command.disableBallAvoidance();
return world_model()->ball.isMovingTowards(robot()->pose.pos, 10.0);
});

addStateFunction(
KickState::POSITIVE_REDIRECT_KICK,
[this](const ConsaiVisualizerWrapper::SharedPtr & visualizer) {
visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::POSITIVE_REDIRECT_KICK");
// ボールラインに沿って追いかけつつ、角度はtargetへ向ける
const auto & ball_pos = world_model()->ball.pos;
command.lookAtFrom(getParameter<Point>("target"), ball_pos);

const auto & ball_vel_normed = world_model()->ball.vel.normalized();
Segment ball_line{ball_pos - ball_vel_normed * 10, ball_pos + ball_vel_normed * 10};
auto [distance, closest_point] = getClosestPointAndDistance(ball_pos, ball_line);
if ((ball_pos - closest_point).dot(ball_vel_normed) > 0) {
// 通り過ぎていれば追いかけて蹴る
auto target_pos = [&]() -> Point {
if (distance < 0.1) {
return ball_pos + ball_vel_normed;
} else {
return closest_point + ball_vel_normed * distance;
}
}();
command.setDribblerTargetPosition(target_pos);
command.kickStraight(0.3);
command.disableBallAvoidance();
} else {
// まだだったら避ける
command.setTargetPosition(
closest_point + (robot()->pose.pos - closest_point).normalized() * 0.3);
}

return Status::RUNNING;
});

addTransition(KickState::POSITIVE_REDIRECT_KICK, KickState::ENTRY_POINT, [this]() {
return !world_model()->ball.isMovingAwayFrom(robot()->pose.pos, 10.0) or
!world_model()->ball.isMovingTowards(getParameter<Point>("target"), 30.0);
});

addStateFunction(
KickState::REDIRECT_KICK, [this](const ConsaiVisualizerWrapper::SharedPtr & visualizer) {
visualizer->addPoint(robot()->pose.pos, 0, "", 1., "Kick::REDIRECT_KICK");
Expand Down
2 changes: 1 addition & 1 deletion crane_robot_skills/src/attacker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ Attacker::Attacker(RobotCommandWrapperBase::SharedPtr & base)
AttackerState::CUT_THEIR_PASS,
[this](const ConsaiVisualizerWrapper::SharedPtr & visualizer) -> Status {
visualizer->addCircle(robot()->pose.pos, 0.25, 1, "blue", "white", 0.5);
receive_skill.setParameter("enable_redirect", true);
receive_skill.setParameter("enable_redirect", false);
receive_skill.setParameter("policy", std::string("min_slack"));
return receive_skill.run(visualizer);
});
Expand Down