From 35bb56db6543451fb07436dabbb4a3d1496aae06 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Sat, 24 Feb 2024 07:43:56 +0900 Subject: [PATCH 1/4] =?UTF-8?q?=E3=82=B3=E3=83=9F=E3=83=83=E3=83=88?= =?UTF-8?q?=E6=BC=8F=E3=82=8C?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- crane_robot_skills/include/crane_robot_skills/skill_base.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crane_robot_skills/include/crane_robot_skills/skill_base.hpp b/crane_robot_skills/include/crane_robot_skills/skill_base.hpp index 1d773a133..dc9ae2af4 100644 --- a/crane_robot_skills/include/crane_robot_skills/skill_base.hpp +++ b/crane_robot_skills/include/crane_robot_skills/skill_base.hpp @@ -174,7 +174,7 @@ class SkillBase : public SkillInterface } Status run( - ConsaiVisualizerWrapper::SharedPtr visualizer, + const ConsaiVisualizerWrapper::SharedPtr & visualizer, std::optional> parameters_opt = std::nullopt) override { From 1733c5d0f6aa88cff78b0051f485dc1d02c5d415 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 20:14:19 +0900 Subject: [PATCH 2/4] =?UTF-8?q?OurKickOffPlanner=E3=81=A7=E3=82=8F?= =?UTF-8?q?=E3=81=96=E3=82=8F=E3=81=96=E4=B8=80=E7=95=AA=E9=81=A0=E3=81=84?= =?UTF-8?q?=E3=83=AD=E3=83=9C=E3=83=83=E3=83=88=E3=82=92=E5=89=B2=E3=82=8A?= =?UTF-8?q?=E5=BD=93=E3=81=A6=E3=81=A6=E3=81=84=E3=81=9F=E3=83=90=E3=82=B0?= =?UTF-8?q?=E3=82=92=E4=BF=AE=E6=AD=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../include/crane_planner_plugins/our_kickoff_planner.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/our_kickoff_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/our_kickoff_planner.hpp index 8ee729f48..8e10eeb24 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/our_kickoff_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/our_kickoff_planner.hpp @@ -60,7 +60,7 @@ class OurKickOffPlanner : public PlannerBase // 一番ボールに近いロボットをkickoff attack auto best_attacker = std::max_element( selectable_robots.begin(), selectable_robots.end(), [this](const auto & a, const auto & b) { - return world_model->getOurRobot(a)->getDistance(world_model->ball.pos) < + return world_model->getOurRobot(a)->getDistance(world_model->ball.pos) > world_model->getOurRobot(b)->getDistance(world_model->ball.pos); }); Point supporter_pos{0.0, 2.0}; @@ -74,7 +74,7 @@ class OurKickOffPlanner : public PlannerBase // bの方大きくない => best_attackerであるbが除外される return false; } else { - return world_model->getOurRobot(a)->getDistance(supporter_pos) < + return world_model->getOurRobot(a)->getDistance(supporter_pos) > world_model->getOurRobot(b)->getDistance(supporter_pos); } }); From fb8d61a5c69bcfc16ac91a580a2c0be6d18d8fd7 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 23 Feb 2024 19:09:36 +0900 Subject: [PATCH 3/4] =?UTF-8?q?=E3=83=95=E3=82=A9=E3=83=BC=E3=83=A1?= =?UTF-8?q?=E3=83=BC=E3=82=B7=E3=83=A7=E3=83=B3=E3=82=92=E7=B5=84=E3=82=93?= =?UTF-8?q?=E3=81=A0=E3=81=A8=E3=81=8D=E3=81=AB=E3=83=9C=E3=83=BC=E3=83=AB?= =?UTF-8?q?=E3=81=AB=E8=BF=91=E3=81=99=E3=81=8E=E3=81=9F=E3=81=AE=E3=81=A7?= =?UTF-8?q?=E4=BF=AE=E6=AD=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../crane_planner_plugins/formation_planner.hpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/session/crane_planner_plugins/include/crane_planner_plugins/formation_planner.hpp b/session/crane_planner_plugins/include/crane_planner_plugins/formation_planner.hpp index f40cdd556..75f4d2035 100644 --- a/session/crane_planner_plugins/include/crane_planner_plugins/formation_planner.hpp +++ b/session/crane_planner_plugins/include/crane_planner_plugins/formation_planner.hpp @@ -37,12 +37,12 @@ class FormationPlanner : public PlannerBase std::vector getFormationPoints(int robot_num) { std::vector formation_points; - formation_points.emplace_back(0.5, 0.0); - formation_points.emplace_back(0.8, 0.5); - formation_points.emplace_back(0.8, -0.5); - formation_points.emplace_back(1.5, 0.0); - formation_points.emplace_back(1.5, 1.0); - formation_points.emplace_back(1.5, -1.0); + formation_points.emplace_back(0.6, 0.0); + formation_points.emplace_back(0.9, 0.5); + formation_points.emplace_back(0.9, -0.5); + formation_points.emplace_back(1.6, 0.0); + formation_points.emplace_back(1.6, 1.0); + formation_points.emplace_back(1.6, -1.0); if (world_model->getOurGoalCenter().x() < 0.0) { for (auto & point : formation_points) { From 46c5afdc7a4fa3be48a2e86215a7437be972829b Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Sat, 24 Feb 2024 00:28:07 +0900 Subject: [PATCH 4/4] =?UTF-8?q?=E3=82=A2=E3=82=BF=E3=83=83=E3=82=AB?= =?UTF-8?q?=E3=83=BC=E8=B7=9D=E9=9B=A2=E5=A4=89=E6=9B=B4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../include/crane_planner_plugins/attacker_planner.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 db541e2c3..de7fda5b5 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 @@ -45,7 +45,7 @@ class AttackerPlanner : public PlannerBase 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; + Point best_target = world_model->ball.pos + getNormVec(best_angle) * 0.3; // シュートの隙がないときは仲間へパス if (goal_angle_width < 0.07) {