From f68f0ddeb589002c01e974e019c729b65c4caf8d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 07:26:03 +0900 Subject: [PATCH 1/9] =?UTF-8?q?Goalie=E3=82=B9=E3=82=AD=E3=83=AB=E3=81=AE?= =?UTF-8?q?=E5=AE=A3=E8=A8=80=E3=81=A8=E5=AE=9F=E8=A3=85=E3=82=92=E5=88=86?= =?UTF-8?q?=E5=89=B2?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../include/crane_robot_skills/goalie.hpp | 89 +------------------ crane_robot_skills/src/goalie.cpp | 88 ++++++++++++++++++ 2 files changed, 90 insertions(+), 87 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/goalie.hpp b/crane_robot_skills/include/crane_robot_skills/goalie.hpp index b6d9afbde..2293351fb 100644 --- a/crane_robot_skills/include/crane_robot_skills/goalie.hpp +++ b/crane_robot_skills/include/crane_robot_skills/goalie.hpp @@ -20,94 +20,9 @@ class Goalie : public SkillBase<> public: explicit Goalie(uint8_t id, const std::shared_ptr & world_model); - void emitBallFromPenaltyArea(crane::RobotCommandWrapper & target) - { - auto ball = world_model->ball.pos; - // パスできるロボットのリストアップ - auto passable_robot_list = world_model->ours.getAvailableRobots(target.robot->id); - passable_robot_list.erase( - std::remove_if( - passable_robot_list.begin(), passable_robot_list.end(), - [&](const RobotInfo::SharedPtr & r) { - // 敵に塞がれていたら除外 - Segment ball_to_robot_line(ball, r->pose.pos); - for (const auto & enemy : world_model->theirs.getAvailableRobots()) { - auto dist = bg::distance(ball_to_robot_line, enemy->pose.pos); - if (dist < 0.2) { - return true; - } - } - return false; - }), - passable_robot_list.end()); + void emitBallFromPenaltyArea(crane::RobotCommandWrapper & target); - Point pass_target = [&]() { - if (not passable_robot_list.empty()) { - // TODO(HansRobo): いい感じのロボットを選ぶようにする - return passable_robot_list.front()->pose.pos; - } else { - return Point{0, 0}; - } - }(); - - Point intermediate_point = ball + (ball - pass_target).normalized() * 0.2f; - double angle_ball_to_target = getAngle(pass_target - ball); - double dot = (world_model->ball.pos - target.robot->pose.pos) - .normalized() - .dot((pass_target - world_model->ball.pos).normalized()); - // ボールと目標の延長線上にいない && 角度があってないときは,中間ポイントを経由 - if ( - dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, target.robot->pose.theta)) > 0.05) { - target.setTargetPosition(intermediate_point); - target.enableCollisionAvoidance(); - } else { - target.setTargetPosition(world_model->ball.pos); - target.kickWithChip(0.4).disableCollisionAvoidance(); - target.enableCollisionAvoidance(); - target.disableBallAvoidance(); - } - target.setTargetTheta(getAngle(pass_target - ball)); - target.disableGoalAreaAvoidance(); - } - - void inplay(crane::RobotCommandWrapper & target, bool enable_emit = true) - { - auto goals = world_model->getOurGoalPosts(); - auto ball = world_model->ball.pos; - // シュートチェック - Segment goal_line(goals.first, goals.second); - Segment ball_line(ball, ball + world_model->ball.vel.normalized() * 20.f); - std::vector intersections; - bg::intersection(ball_line, Segment{goals.first, goals.second}, intersections); - if (not intersections.empty() && world_model->ball.vel.norm() > 0.5f) { - // シュートブロック - phase = "シュートブロック"; - ClosestPoint result; - bg::closest_point(ball_line, target.robot->pose.pos, result); - target.setTargetPosition(result.closest_point); - target.setTargetTheta(getAngle(-world_model->ball.vel)); - } else { - if (world_model->ball.isStopped() && world_model->isFriendDefenseArea(ball) && enable_emit) { - // ボールが止まっていて,味方ペナルティエリア内にあるときは,ペナルティエリア外に出す - phase = "ボール排出"; - emitBallFromPenaltyArea(target); - } else { - phase = ""; - const double BLOCK_DIST = 0.15; - // 範囲外のときは正面に構える - if (not world_model->isFieldInside(ball)) { - phase += "正面で"; - ball << 0, 0; - } - - phase = "ボールを待ち受ける"; - Point goal_center = world_model->getOurGoalCenter(); - goal_center << goals.first.x(), 0.0f; - target.setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); - target.lookAtBall(); - } - } - } + void inplay(crane::RobotCommandWrapper & target, bool enable_emit = true); void print(std::ostream & os) const override { os << "[Goalie] " << phase; } diff --git a/crane_robot_skills/src/goalie.cpp b/crane_robot_skills/src/goalie.cpp index 98f6b27aa..142b187d3 100644 --- a/crane_robot_skills/src/goalie.cpp +++ b/crane_robot_skills/src/goalie.cpp @@ -40,4 +40,92 @@ Goalie::Goalie(uint8_t id, const std::shared_ptr & world_mode return Status::RUNNING; }); } + +void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & target) +{ + auto ball = world_model->ball.pos; + // パスできるロボットのリストアップ + auto passable_robot_list = world_model->ours.getAvailableRobots(target.robot->id); + passable_robot_list.erase( + std::remove_if( + passable_robot_list.begin(), passable_robot_list.end(), + [&](const RobotInfo::SharedPtr & r) { + // 敵に塞がれていたら除外 + Segment ball_to_robot_line(ball, r->pose.pos); + for (const auto & enemy : world_model->theirs.getAvailableRobots()) { + auto dist = bg::distance(ball_to_robot_line, enemy->pose.pos); + if (dist < 0.2) { + return true; + } + } + return false; + }), + passable_robot_list.end()); + + Point pass_target = [&]() { + if (not passable_robot_list.empty()) { + // TODO(HansRobo): いい感じのロボットを選ぶようにする + return passable_robot_list.front()->pose.pos; + } else { + return Point{0, 0}; + } + }(); + + Point intermediate_point = ball + (ball - pass_target).normalized() * 0.2f; + double angle_ball_to_target = getAngle(pass_target - ball); + double dot = (world_model->ball.pos - target.robot->pose.pos) + .normalized() + .dot((pass_target - world_model->ball.pos).normalized()); + // ボールと目標の延長線上にいない && 角度があってないときは,中間ポイントを経由 + if (dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, target.robot->pose.theta)) > 0.05) { + target.setTargetPosition(intermediate_point); + target.enableCollisionAvoidance(); + } else { + target.setTargetPosition(world_model->ball.pos); + target.kickWithChip(0.4).disableCollisionAvoidance(); + target.enableCollisionAvoidance(); + target.disableBallAvoidance(); + } + target.setTargetTheta(getAngle(pass_target - ball)); + target.disableGoalAreaAvoidance(); +} + +void Goalie::inplay(RobotCommandWrapper & target, bool enable_emit) +{ + auto goals = world_model->getOurGoalPosts(); + auto ball = world_model->ball.pos; + // シュートチェック + Segment goal_line(goals.first, goals.second); + Segment ball_line(ball, ball + world_model->ball.vel.normalized() * 20.f); + std::vector intersections; + bg::intersection(ball_line, Segment{goals.first, goals.second}, intersections); + if (not intersections.empty() && world_model->ball.vel.norm() > 0.5f) { + // シュートブロック + phase = "シュートブロック"; + ClosestPoint result; + bg::closest_point(ball_line, target.robot->pose.pos, result); + target.setTargetPosition(result.closest_point); + target.setTargetTheta(getAngle(-world_model->ball.vel)); + } else { + if (world_model->ball.isStopped() && world_model->isFriendDefenseArea(ball) && enable_emit) { + // ボールが止まっていて,味方ペナルティエリア内にあるときは,ペナルティエリア外に出す + phase = "ボール排出"; + emitBallFromPenaltyArea(target); + } else { + phase = ""; + const double BLOCK_DIST = 0.15; + // 範囲外のときは正面に構える + if (not world_model->isFieldInside(ball)) { + phase += "正面で"; + ball << 0, 0; + } + + phase = "ボールを待ち受ける"; + Point goal_center = world_model->getOurGoalCenter(); + goal_center << goals.first.x(), 0.0f; + target.setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); + target.lookAtBall(); + } + } +} } // namespace crane::skills From 46ff2cda5c917c75dff59ca51dd05290fc9b2e53 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 07:29:13 +0900 Subject: [PATCH 2/9] target->command --- .../include/crane_robot_skills/goalie.hpp | 4 +- crane_robot_skills/src/goalie.cpp | 39 ++++++++++--------- 2 files changed, 22 insertions(+), 21 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/goalie.hpp b/crane_robot_skills/include/crane_robot_skills/goalie.hpp index 2293351fb..63a2692bc 100644 --- a/crane_robot_skills/include/crane_robot_skills/goalie.hpp +++ b/crane_robot_skills/include/crane_robot_skills/goalie.hpp @@ -20,9 +20,9 @@ class Goalie : public SkillBase<> public: explicit Goalie(uint8_t id, const std::shared_ptr & world_model); - void emitBallFromPenaltyArea(crane::RobotCommandWrapper & target); + void emitBallFromPenaltyArea(crane::RobotCommandWrapper & command); - void inplay(crane::RobotCommandWrapper & target, bool enable_emit = true); + void inplay(crane::RobotCommandWrapper & command, bool enable_emit = true); void print(std::ostream & os) const override { os << "[Goalie] " << phase; } diff --git a/crane_robot_skills/src/goalie.cpp b/crane_robot_skills/src/goalie.cpp index 142b187d3..16718e876 100644 --- a/crane_robot_skills/src/goalie.cpp +++ b/crane_robot_skills/src/goalie.cpp @@ -41,11 +41,11 @@ Goalie::Goalie(uint8_t id, const std::shared_ptr & world_mode }); } -void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & target) +void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & command) { auto ball = world_model->ball.pos; // パスできるロボットのリストアップ - auto passable_robot_list = world_model->ours.getAvailableRobots(target.robot->id); + auto passable_robot_list = world_model->ours.getAvailableRobots(command.robot->id); passable_robot_list.erase( std::remove_if( passable_robot_list.begin(), passable_robot_list.end(), @@ -73,24 +73,25 @@ void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & target) Point intermediate_point = ball + (ball - pass_target).normalized() * 0.2f; double angle_ball_to_target = getAngle(pass_target - ball); - double dot = (world_model->ball.pos - target.robot->pose.pos) + double dot = (world_model->ball.pos - command.robot->pose.pos) .normalized() .dot((pass_target - world_model->ball.pos).normalized()); // ボールと目標の延長線上にいない && 角度があってないときは,中間ポイントを経由 - if (dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, target.robot->pose.theta)) > 0.05) { - target.setTargetPosition(intermediate_point); - target.enableCollisionAvoidance(); + if ( + dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, command.robot->pose.theta)) > 0.05) { + command.setTargetPosition(intermediate_point); + command.enableCollisionAvoidance(); } else { - target.setTargetPosition(world_model->ball.pos); - target.kickWithChip(0.4).disableCollisionAvoidance(); - target.enableCollisionAvoidance(); - target.disableBallAvoidance(); + command.setTargetPosition(world_model->ball.pos); + command.kickWithChip(0.4).disableCollisionAvoidance(); + command.enableCollisionAvoidance(); + command.disableBallAvoidance(); } - target.setTargetTheta(getAngle(pass_target - ball)); - target.disableGoalAreaAvoidance(); + command.setTargetTheta(getAngle(pass_target - ball)); + command.disableGoalAreaAvoidance(); } -void Goalie::inplay(RobotCommandWrapper & target, bool enable_emit) +void Goalie::inplay(RobotCommandWrapper & command, bool enable_emit) { auto goals = world_model->getOurGoalPosts(); auto ball = world_model->ball.pos; @@ -103,14 +104,14 @@ void Goalie::inplay(RobotCommandWrapper & target, bool enable_emit) // シュートブロック phase = "シュートブロック"; ClosestPoint result; - bg::closest_point(ball_line, target.robot->pose.pos, result); - target.setTargetPosition(result.closest_point); - target.setTargetTheta(getAngle(-world_model->ball.vel)); + bg::closest_point(ball_line, command.robot->pose.pos, result); + command.setTargetPosition(result.closest_point); + command.setTargetTheta(getAngle(-world_model->ball.vel)); } else { if (world_model->ball.isStopped() && world_model->isFriendDefenseArea(ball) && enable_emit) { // ボールが止まっていて,味方ペナルティエリア内にあるときは,ペナルティエリア外に出す phase = "ボール排出"; - emitBallFromPenaltyArea(target); + emitBallFromPenaltyArea(command); } else { phase = ""; const double BLOCK_DIST = 0.15; @@ -123,8 +124,8 @@ void Goalie::inplay(RobotCommandWrapper & target, bool enable_emit) phase = "ボールを待ち受ける"; Point goal_center = world_model->getOurGoalCenter(); goal_center << goals.first.x(), 0.0f; - target.setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); - target.lookAtBall(); + command.setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); + command.lookAtBall(); } } } From a7a3f0b0b4404247e2bf3d9823e2525384ca23b3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 15:58:18 +0900 Subject: [PATCH 3/9] =?UTF-8?q?=E3=83=93=E3=83=AB=E3=83=89=E3=82=A8?= =?UTF-8?q?=E3=83=A9=E3=83=BC=E4=BF=AE=E6=AD=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- crane_robot_skills/src/goalie.cpp | 36 +++++++++++++++---------------- 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/crane_robot_skills/src/goalie.cpp b/crane_robot_skills/src/goalie.cpp index c2ed0d8d7..ae8cca30c 100644 --- a/crane_robot_skills/src/goalie.cpp +++ b/crane_robot_skills/src/goalie.cpp @@ -37,11 +37,11 @@ Goalie::Goalie(uint8_t id, const std::shared_ptr & wm) }); } -void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & command) +void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper::SharedPtr & command) { auto ball = world_model->ball.pos; // パスできるロボットのリストアップ - auto passable_robot_list = world_model->ours.getAvailableRobots(command.robot->id); + auto passable_robot_list = world_model->ours.getAvailableRobots(command->robot->id); passable_robot_list.erase( std::remove_if( passable_robot_list.begin(), passable_robot_list.end(), @@ -69,25 +69,25 @@ void Goalie::emitBallFromPenaltyArea(RobotCommandWrapper & command) Point intermediate_point = ball + (ball - pass_target).normalized() * 0.2f; double angle_ball_to_target = getAngle(pass_target - ball); - double dot = (world_model->ball.pos - command.robot->pose.pos) + double dot = (world_model->ball.pos - command->robot->pose.pos) .normalized() .dot((pass_target - world_model->ball.pos).normalized()); // ボールと目標の延長線上にいない && 角度があってないときは,中間ポイントを経由 if ( - dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, command.robot->pose.theta)) > 0.05) { - command.setTargetPosition(intermediate_point); - command.enableCollisionAvoidance(); + dot < 0.95 || std::abs(getAngleDiff(angle_ball_to_target, command->robot->pose.theta)) > 0.05) { + command->setTargetPosition(intermediate_point); + command->enableCollisionAvoidance(); } else { - command.setTargetPosition(world_model->ball.pos); - command.kickWithChip(0.4).disableCollisionAvoidance(); - command.enableCollisionAvoidance(); - command.disableBallAvoidance(); + command->setTargetPosition(world_model->ball.pos); + command->kickWithChip(0.4).disableCollisionAvoidance(); + command->enableCollisionAvoidance(); + command->disableBallAvoidance(); } - command.setTargetTheta(getAngle(pass_target - ball)); - command.disableGoalAreaAvoidance(); + command->setTargetTheta(getAngle(pass_target - ball)); + command->disableGoalAreaAvoidance(); } -void Goalie::inplay(RobotCommandWrapper & command, bool enable_emit) +void Goalie::inplay(RobotCommandWrapper::SharedPtr & command, bool enable_emit) { auto goals = world_model->getOurGoalPosts(); auto ball = world_model->ball.pos; @@ -100,9 +100,9 @@ void Goalie::inplay(RobotCommandWrapper & command, bool enable_emit) // シュートブロック phase = "シュートブロック"; ClosestPoint result; - bg::closest_point(ball_line, command.robot->pose.pos, result); - command.setTargetPosition(result.closest_point); - command.setTargetTheta(getAngle(-world_model->ball.vel)); + bg::closest_point(ball_line, command->robot->pose.pos, result); + command->setTargetPosition(result.closest_point); + command->setTargetTheta(getAngle(-world_model->ball.vel)); } else { if (world_model->ball.isStopped() && world_model->isFriendDefenseArea(ball) && enable_emit) { // ボールが止まっていて,味方ペナルティエリア内にあるときは,ペナルティエリア外に出す @@ -120,8 +120,8 @@ void Goalie::inplay(RobotCommandWrapper & command, bool enable_emit) phase = "ボールを待ち受ける"; Point goal_center = world_model->getOurGoalCenter(); goal_center << goals.first.x(), 0.0f; - command.setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); - command.lookAtBall(); + command->setTargetPosition(goal_center + (ball - goal_center).normalized() * BLOCK_DIST); + command->lookAtBall(); } } } From 5170c35af79b12c15d1698a09f82f204ea753548 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:02:47 +0900 Subject: [PATCH 4/9] =?UTF-8?q?=E3=83=87=E3=83=90=E3=83=83=E3=82=B0?= =?UTF-8?q?=E5=87=BA=E5=8A=9B?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp index 8078f1f27..b42a9c139 100644 --- a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp +++ b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp @@ -57,10 +57,13 @@ class PenaltyKick : public SkillBase } auto [best_target, goal_angle_width] = getBestShootTargetWithWidth(); + visualizer->addPoint(best_target.x(), best_target.y(), 1, "red", 1.0, "best_target"); // 経由ポイント Point intermediate_point = world_model->ball.pos + (world_model->ball.pos - best_target).normalized() * 0.2; + visualizer->addPoint( + intermediate_point.x(), intermediate_point.y(), 1, "red", 1.0, "intermediate_point"); double dot = (robot->pose.pos - world_model->ball.pos) .normalized() From 422cc3128d31d0e382bf11c252eafa2b1bd1a579 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:03:24 +0900 Subject: [PATCH 5/9] =?UTF-8?q?=E8=A7=92=E5=BA=A6=E8=A8=88=E7=AE=97?= =?UTF-8?q?=E3=81=A7=E7=89=B9=E7=95=B0=E7=82=B9=E3=82=92=E5=9B=9E=E9=81=BF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../crane_robot_skills/penalty_kick.hpp | 24 ++++++++++++++++--- 1 file changed, 21 insertions(+), 3 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp index b42a9c139..898045df0 100644 --- a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp +++ b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp @@ -103,13 +103,25 @@ class PenaltyKick : public SkillBase Interval goal_range; auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); + if (goal_posts.first.x() < 0.) { + goal_range.append( + normalizeAngle(getAngle(goal_posts.first - ball) + M_PI), + normalizeAngle(getAngle(goal_posts.second - ball) + M_PI)); + } else { + goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); + } for (auto & enemy : world_model->theirs.getAvailableRobots()) { double distance = enemy->getDistance(ball); constexpr double MACHINE_RADIUS = 0.1; - double center_angle = getAngle(enemy->pose.pos - ball); + double center_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle(getAngle(enemy->pose.pos - ball) + M_PI); + } else { + return getAngle(enemy->pose.pos - ball); + } + }(); double diff_angle = atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); @@ -118,7 +130,13 @@ class PenaltyKick : public SkillBase auto largest_interval = goal_range.getLargestInterval(); - double target_angle = (largest_interval.first + largest_interval.second) / 2.0; + double target_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle((largest_interval.first + largest_interval.second) / 2.0 - M_PI); + } else { + return (largest_interval.first + largest_interval.second) / 2.0; + } + }(); return { ball + getNormVec(target_angle) * 0.5, largest_interval.second - largest_interval.first}; From 0b1d430fe677a74b2c0169108cccba54786f4142 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:04:46 +0900 Subject: [PATCH 6/9] =?UTF-8?q?=E8=A7=92=E5=BA=A6=E8=A8=88=E7=AE=97?= =?UTF-8?q?=E3=81=A7=E7=89=B9=E7=95=B0=E7=82=B9=E3=82=92=E5=9B=9E=E9=81=BF?= =?UTF-8?q?=E3=81=97=E3=81=9F=E3=81=AE=E3=82=92SimpleAttacker=E3=81=AB?= =?UTF-8?q?=E9=82=84=E5=85=83?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../crane_robot_skills/simple_attacker.hpp | 28 +++++++++++++++---- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp b/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp index 5298af496..a987e4274 100644 --- a/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp +++ b/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp @@ -32,13 +32,25 @@ class SimpleAttacker : public SkillBase<> Interval goal_range; auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); + if (goal_posts.first.x() < 0.) { + goal_range.append( + normalizeAngle(getAngle(goal_posts.first - ball) + M_PI), + normalizeAngle(getAngle(goal_posts.second - ball) + M_PI)); + } else { + goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); + } - for (auto & enemy : world_model->theirs.robots) { - double distance = (ball - enemy->pose.pos).norm(); + for (auto & enemy : world_model->theirs.getAvailableRobots()) { + double distance = enemy->getDistance(ball); constexpr double MACHINE_RADIUS = 0.1; - double center_angle = getAngle(enemy->pose.pos - ball); + double center_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle(getAngle(enemy->pose.pos - ball) + M_PI); + } else { + return getAngle(enemy->pose.pos - ball); + } + }(); double diff_angle = atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); @@ -47,7 +59,13 @@ class SimpleAttacker : public SkillBase<> auto largest_interval = goal_range.getLargestInterval(); - double target_angle = (largest_interval.first + largest_interval.second) / 2.0; + double target_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle((largest_interval.first + largest_interval.second) / 2.0 - M_PI); + } else { + return (largest_interval.first + largest_interval.second) / 2.0; + } + }(); return { ball + getNormVec(target_angle) * 0.5, largest_interval.second - largest_interval.first}; From 918a86ea7c3e0f0ca1dc867e80bc2051f984ef70 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:12:06 +0900 Subject: [PATCH 7/9] =?UTF-8?q?=E3=82=B7=E3=83=A5=E3=83=BC=E3=83=88?= =?UTF-8?q?=E3=82=92=E6=AD=A2=E3=82=81=E3=82=8B=E5=A0=B4=E6=89=80=E3=81=8C?= =?UTF-8?q?=E9=81=A0=E3=81=84=E5=A0=B4=E5=90=88=E3=81=AB=E5=8A=A0=E9=80=9F?= =?UTF-8?q?=E3=81=99=E3=82=8B?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- crane_robot_skills/src/goalie.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/crane_robot_skills/src/goalie.cpp b/crane_robot_skills/src/goalie.cpp index ae8cca30c..b6d8808c3 100644 --- a/crane_robot_skills/src/goalie.cpp +++ b/crane_robot_skills/src/goalie.cpp @@ -96,6 +96,7 @@ void Goalie::inplay(RobotCommandWrapper::SharedPtr & command, bool enable_emit) Segment ball_line(ball, ball + world_model->ball.vel.normalized() * 20.f); std::vector intersections; bg::intersection(ball_line, Segment{goals.first, goals.second}, intersections); + command->setTerminalVelocity(0.0); if (not intersections.empty() && world_model->ball.vel.norm() > 0.5f) { // シュートブロック phase = "シュートブロック"; @@ -103,6 +104,9 @@ void Goalie::inplay(RobotCommandWrapper::SharedPtr & command, bool enable_emit) bg::closest_point(ball_line, command->robot->pose.pos, result); command->setTargetPosition(result.closest_point); command->setTargetTheta(getAngle(-world_model->ball.vel)); + if (command->robot->getDistance(ball) > 0.3) { + command->setTerminalVelocity(2.0); + } } else { if (world_model->ball.isStopped() && world_model->isFriendDefenseArea(ball) && enable_emit) { // ボールが止まっていて,味方ペナルティエリア内にあるときは,ペナルティエリア外に出す From e7c4050e7159f8b1a7c0d7b6f5ce80c1d0fbdd47 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:28:38 +0900 Subject: [PATCH 8/9] =?UTF-8?q?=E8=89=B2=E3=80=85=E3=81=AA=E3=81=A8?= =?UTF-8?q?=E3=81=93=E3=82=8D=E3=81=A7=E4=BD=BF=E3=81=86=E5=87=A6=E7=90=86?= =?UTF-8?q?=E3=81=AA=E3=81=AE=E3=81=A7WorldModelWrapper=E3=81=AB=E8=BF=BD?= =?UTF-8?q?=E5=8A=A0=E3=81=97=E3=81=9F?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../crane_robot_skills/penalty_kick.hpp | 51 ++----------------- .../crane_robot_skills/simple_attacker.hpp | 46 ----------------- crane_robot_skills/src/simple_attacker.cpp | 4 +- .../world_model_wrapper.hpp | 49 ++++++++++++++++++ 4 files changed, 55 insertions(+), 95 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp index 898045df0..b74d76829 100644 --- a/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp +++ b/crane_robot_skills/include/crane_robot_skills/penalty_kick.hpp @@ -56,7 +56,9 @@ class PenaltyKick : public SkillBase start_ball_point = world_model->ball.pos; } - auto [best_target, goal_angle_width] = getBestShootTargetWithWidth(); + auto [best_angle, goal_angle_width] = + world_model->getLargestGoalAngleRangeFromPoint(world_model->ball.pos); + Point best_target = world_model->ball.pos + getNormVec(best_angle) * 0.5; visualizer->addPoint(best_target.x(), best_target.y(), 1, "red", 1.0, "best_target"); // 経由ポイント @@ -95,53 +97,6 @@ class PenaltyKick : public SkillBase }); } - // SimpleAttackerからコピー - auto getBestShootTargetWithWidth() -> std::pair - { - const auto & ball = world_model->ball.pos; - - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - if (goal_posts.first.x() < 0.) { - goal_range.append( - normalizeAngle(getAngle(goal_posts.first - ball) + M_PI), - normalizeAngle(getAngle(goal_posts.second - ball) + M_PI)); - } else { - goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); - } - - for (auto & enemy : world_model->theirs.getAvailableRobots()) { - double distance = enemy->getDistance(ball); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = [&]() { - if (goal_posts.first.x() < 0.) { - return normalizeAngle(getAngle(enemy->pose.pos - ball) + M_PI); - } else { - return getAngle(enemy->pose.pos - ball); - } - }(); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - - double target_angle = [&]() { - if (goal_posts.first.x() < 0.) { - return normalizeAngle((largest_interval.first + largest_interval.second) / 2.0 - M_PI); - } else { - return (largest_interval.first + largest_interval.second) / 2.0; - } - }(); - - return { - ball + getNormVec(target_angle) * 0.5, largest_interval.second - largest_interval.first}; - } - void print(std::ostream & os) const override { os << "[Idle] stop_by_position: " << getParameter("stop_by_position") ? "true" : "false"; diff --git a/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp b/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp index a987e4274..4d91b84a2 100644 --- a/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp +++ b/crane_robot_skills/include/crane_robot_skills/simple_attacker.hpp @@ -24,52 +24,6 @@ class SimpleAttacker : public SkillBase<> { os << "[Idle] stop_by_position: " << getParameter("stop_by_position") ? "true" : "false"; } - - auto getBestShootTargetWithWidth() -> std::pair - { - const auto & ball = world_model->ball.pos; - - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - if (goal_posts.first.x() < 0.) { - goal_range.append( - normalizeAngle(getAngle(goal_posts.first - ball) + M_PI), - normalizeAngle(getAngle(goal_posts.second - ball) + M_PI)); - } else { - goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); - } - - for (auto & enemy : world_model->theirs.getAvailableRobots()) { - double distance = enemy->getDistance(ball); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = [&]() { - if (goal_posts.first.x() < 0.) { - return normalizeAngle(getAngle(enemy->pose.pos - ball) + M_PI); - } else { - return getAngle(enemy->pose.pos - ball); - } - }(); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - - double target_angle = [&]() { - if (goal_posts.first.x() < 0.) { - return normalizeAngle((largest_interval.first + largest_interval.second) / 2.0 - M_PI); - } else { - return (largest_interval.first + largest_interval.second) / 2.0; - } - }(); - - return { - ball + getNormVec(target_angle) * 0.5, largest_interval.second - largest_interval.first}; - } }; } // namespace crane::skills #endif // CRANE_ROBOT_SKILLS__SIMPLE_ATTACKER_HPP_ diff --git a/crane_robot_skills/src/simple_attacker.cpp b/crane_robot_skills/src/simple_attacker.cpp index 14f517695..fcd63a46e 100644 --- a/crane_robot_skills/src/simple_attacker.cpp +++ b/crane_robot_skills/src/simple_attacker.cpp @@ -13,7 +13,9 @@ SimpleAttacker::SimpleAttacker(uint8_t id, const std::shared_ptr Status { - auto [best_target, goal_angle_width] = getBestShootTargetWithWidth(); + auto [best_angle, goal_angle_width] = + world_model->getLargestGoalAngleRangeFromPoint(world_model->ball.pos); + Point best_target = world_model->ball.pos + getNormVec(best_angle) * 0.5; // シュートの隙がないときは仲間へパス if (goal_angle_width < 0.07) { diff --git a/utility/crane_msg_wrappers/include/crane_msg_wrappers/world_model_wrapper.hpp b/utility/crane_msg_wrappers/include/crane_msg_wrappers/world_model_wrapper.hpp index 2b8a1e06f..90aed1824 100644 --- a/utility/crane_msg_wrappers/include/crane_msg_wrappers/world_model_wrapper.hpp +++ b/utility/crane_msg_wrappers/include/crane_msg_wrappers/world_model_wrapper.hpp @@ -11,6 +11,7 @@ #include #include #include +#include #include #include #include @@ -476,6 +477,54 @@ struct WorldModelWrapper [[nodiscard]] uint8_t getTheirGoalieId() const { return latest_msg.their_goalie_id; } + /** + * + * @param from + * @return {angle, width} + */ + auto getLargestGoalAngleRangeFromPoint(Point from) -> std::pair + { + Interval goal_range; + + auto goal_posts = getTheirGoalPosts(); + if (goal_posts.first.x() < 0.) { + goal_range.append( + normalizeAngle(getAngle(goal_posts.first - from) + M_PI), + normalizeAngle(getAngle(goal_posts.second - from) + M_PI)); + } else { + goal_range.append(getAngle(goal_posts.first - from), getAngle(goal_posts.second - from)); + } + + for (auto & enemy : theirs.getAvailableRobots()) { + double distance = enemy->getDistance(from); + constexpr double MACHINE_RADIUS = 0.1; + + double center_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle(getAngle(enemy->pose.pos - from) + M_PI); + } else { + return getAngle(enemy->pose.pos - from); + } + }(); + double diff_angle = + atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); + + goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); + } + + auto largest_interval = goal_range.getLargestInterval(); + + double target_angle = [&]() { + if (goal_posts.first.x() < 0.) { + return normalizeAngle((largest_interval.first + largest_interval.second) / 2.0 - M_PI); + } else { + return (largest_interval.first + largest_interval.second) / 2.0; + } + }(); + + return {target_angle, largest_interval.second - largest_interval.first}; + } + TeamInfo ours; TeamInfo theirs; From d0a532baf041ad1a12b9be3a84559a3c8c1dd72b Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 17:41:14 +0900 Subject: [PATCH 9/9] =?UTF-8?q?world=5Fmodel->getLargestGoalAngleRangeFrom?= =?UTF-8?q?Point=E3=82=92=E4=BD=BF=E3=81=88=E3=82=8B=E3=81=A8=E3=81=93?= =?UTF-8?q?=E3=82=8D=E3=81=A7=E5=85=A8=E9=83=A8=E4=BD=BF=E3=81=A3=E3=81=A6?= =?UTF-8?q?=E3=81=84=E3=81=8F?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../include/crane_robot_skills/receiver.hpp | 44 ---------------- crane_robot_skills/src/receiver.cpp | 8 +-- .../attacker_planner.hpp | 32 ++---------- .../crane_planner_plugins/receive_planner.hpp | 52 ++----------------- 4 files changed, 13 insertions(+), 123 deletions(-) diff --git a/crane_robot_skills/include/crane_robot_skills/receiver.hpp b/crane_robot_skills/include/crane_robot_skills/receiver.hpp index 116c23612..dd081a331 100644 --- a/crane_robot_skills/include/crane_robot_skills/receiver.hpp +++ b/crane_robot_skills/include/crane_robot_skills/receiver.hpp @@ -44,50 +44,6 @@ class Receiver : public SkillBase<> void print(std::ostream & os) const override { os << "[Receiver]"; } - auto getLargestGoalAngleWidthFromPosition(const Point point) -> double - { - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - point), getAngle(goal_posts.second - point)); - - for (auto & enemy : world_model->theirs.robots) { - double distance = (point - enemy->pose.pos).norm(); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = getAngle(enemy->pose.pos - point); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - return largest_interval.second - largest_interval.first; - } - - auto getLargestGoalAngleFromPosition(const Point point) -> double - { - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - point), getAngle(goal_posts.second - point)); - - for (auto & enemy : world_model->theirs.robots) { - double distance = (point - enemy->pose.pos).norm(); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = getAngle(enemy->pose.pos - point); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - return (largest_interval.second + largest_interval.first) * 0.5; - } - std::vector> getPositionsWithScore(Segment ball_line, Point next_target) { auto points = getPoints(ball_line, 0.05); diff --git a/crane_robot_skills/src/receiver.cpp b/crane_robot_skills/src/receiver.cpp index f45cc882d..e85bab117 100644 --- a/crane_robot_skills/src/receiver.cpp +++ b/crane_robot_skills/src/receiver.cpp @@ -43,7 +43,8 @@ Receiver::Receiver(uint8_t id, const std::shared_ptr & wm) // ゴールとボールの中間方向を向く // TODO(Hansobo): ボールの速さ・キッカーの強さでボールの反射する角度が変わるため、要考慮 - auto goal_angle = getLargestGoalAngleFromPosition(result.closest_point); + auto [goal_angle, width] = + world_model->getLargestGoalAngleRangeFromPoint(result.closest_point); auto to_goal = getNormVec(goal_angle); auto to_ball = (world_model->ball.pos - result.closest_point).normalized(); double intermediate_angle = getAngle(2 * to_goal + to_ball); @@ -74,7 +75,8 @@ Receiver::Receiver(uint8_t id, const std::shared_ptr & wm) continue; } - double score = getLargestGoalAngleWidthFromPosition(dpps_point); + auto [goal_angle, width] = world_model->getLargestGoalAngleRangeFromPoint(dpps_point); + double score = width; const double dist = (robot->pose.pos - dpps_point).norm(); score = score * (1.0 - dist / 10.0); @@ -89,7 +91,7 @@ Receiver::Receiver(uint8_t id, const std::shared_ptr & wm) // ゴールとボールの中間方向を向く Point target_pos{command->latest_msg.target_x.front(), command->latest_msg.target_y.front()}; - auto goal_angle = getLargestGoalAngleFromPosition(target_pos); + auto [goal_angle, width] = world_model->getLargestGoalAngleRangeFromPoint(target_pos); auto to_goal = getNormVec(goal_angle); auto to_ball = (world_model->ball.pos - target_pos).normalized(); command->setTargetTheta(getAngle(to_goal + to_ball)); diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/attacker_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/attacker_planner.hpp index 419b22099..d2a845f58 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/attacker_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/attacker_planner.hpp @@ -42,7 +42,9 @@ class AttackerPlanner : public PlannerBase crane::RobotCommandWrapper target(robot_id.robot_id, world_model); auto robot = world_model->getRobot(robot_id); - auto [best_target, goal_angle_width] = getBestShootTargetWithWidth(); + auto [best_angle, goal_angle_width] = + world_model->getLargestGoalAngleRangeFromPoint(world_model->ball.pos); + Point best_target = world_model->ball.pos + getNormVec(best_angle) * 0.5; // シュートの隙がないときは仲間へパス if (goal_angle_width < 0.07) { @@ -97,34 +99,6 @@ class AttackerPlanner : public PlannerBase return 100.0 / std::max(world_model->getSquareDistanceFromRobotToBall(robot->id), 0.01); }); } - - auto getBestShootTargetWithWidth() -> std::pair - { - const auto & ball = world_model->ball.pos; - - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - ball), getAngle(goal_posts.second - ball)); - - for (auto & enemy : world_model->theirs.robots) { - double distance = (ball - enemy->pose.pos).norm(); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = getAngle(enemy->pose.pos - ball); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - - double target_angle = (largest_interval.first + largest_interval.second) / 2.0; - - return { - ball + getNormVec(target_angle) * 0.5, largest_interval.second - largest_interval.first}; - } }; } // namespace crane diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/receive_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/receive_planner.hpp index 46e30b5a5..15c116f51 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/receive_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/receive_planner.hpp @@ -99,7 +99,8 @@ class ReceivePlanner : public PlannerBase bg::closest_point(robot_info->pose.pos, ball_line, result); // ゴールとボールの中間方向を向く - auto goal_angle = getLargestGoalAngleFromPosition(result.closest_point); + auto [goal_angle, width] = + world_model->getLargestGoalAngleRangeFromPoint(result.closest_point); auto to_goal = getNormVec(goal_angle); auto to_ball = (world_model->ball.pos - result.closest_point).normalized(); double intermediate_angle = getAngle(2 * to_goal + to_ball); @@ -130,7 +131,8 @@ class ReceivePlanner : public PlannerBase continue; } - double score = getLargestGoalAngleWidthFromPosition(dpps_point); + auto [angle, width] = world_model->getLargestGoalAngleRangeFromPoint(dpps_point); + double score = width; const double dist = world_model->getDistanceFromRobot(robot, dpps_point); score = score * (1.0 - dist / 10.0); @@ -145,7 +147,7 @@ class ReceivePlanner : public PlannerBase // ゴールとボールの中間方向を向く Point target_pos{target.latest_msg.target_x.front(), target.latest_msg.target_y.front()}; - auto goal_angle = getLargestGoalAngleFromPosition(target_pos); + auto [goal_angle, width] = world_model->getLargestGoalAngleRangeFromPoint(target_pos); auto to_goal = getNormVec(goal_angle); auto to_ball = (world_model->ball.pos - target_pos).normalized(); target.setTargetTheta(getAngle(to_goal + to_ball)); @@ -250,50 +252,6 @@ class ReceivePlanner : public PlannerBase return ret; } - auto getLargestGoalAngleWidthFromPosition(const Point point) -> double - { - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - point), getAngle(goal_posts.second - point)); - - for (auto & enemy : world_model->theirs.robots) { - double distance = (point - enemy->pose.pos).norm(); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = getAngle(enemy->pose.pos - point); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - return largest_interval.second - largest_interval.first; - } - - auto getLargestGoalAngleFromPosition(const Point point) -> double - { - Interval goal_range; - - auto goal_posts = world_model->getTheirGoalPosts(); - goal_range.append(getAngle(goal_posts.first - point), getAngle(goal_posts.second - point)); - - for (auto & enemy : world_model->theirs.robots) { - double distance = (point - enemy->pose.pos).norm(); - constexpr double MACHINE_RADIUS = 0.1; - - double center_angle = getAngle(enemy->pose.pos - point); - double diff_angle = - atan(MACHINE_RADIUS / std::sqrt(distance * distance - MACHINE_RADIUS * MACHINE_RADIUS)); - - goal_range.erase(center_angle - diff_angle, center_angle + diff_angle); - } - - auto largest_interval = goal_range.getLargestInterval(); - return (largest_interval.second + largest_interval.first) * 0.5; - } - std::vector> getPositionsWithScore(Segment ball_line, Point next_target) { auto points = getPoints(ball_line, 0.05);