From e87e8e3e50dd0cfad1e8c34ad6e3f2d4dfb29271 Mon Sep 17 00:00:00 2001 From: petergarud Date: Mon, 22 Jan 2024 02:18:10 +0000 Subject: [PATCH 1/8] fixed compiler error and targets 7/8 part of goal --- .../planner/line_kick_path_planner.cpp | 18 +++++++++++++----- .../soccer/strategy/agent/position/offense.cpp | 3 +-- 2 files changed, 14 insertions(+), 7 deletions(-) diff --git a/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp b/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp index f12219ffcf4..ad25d67a2ac 100644 --- a/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp +++ b/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp @@ -33,10 +33,18 @@ Trajectory LineKickPathPlanner::plan(const PlanRequest& plan_request) { average_ball_vel_ = apply_low_pass_filter(average_ball_vel_, ball.velocity, 0.8); } - // only process state transition if already started the planning - if (has_created_plan) { - process_state_transition(); - } + // ShapeSet static_obstacles; + // std::vector dynamic_obstacles; + // fill_obstacles(plan_request, &static_obstacles, &dynamic_obstacles, false, nullptr); + + // auto obstacles_with_ball = static_obstacles; + // const RJ::Time cur_time = start_instant.stamp; + // obstacles_with_ball.add( + // make_shared(ball.predict_at(cur_time).position, ball_avoid_distance)); + + // // only plan line kick if not is_done + // if (!this->is_done()) { + state_transition(ball, plan_request.start); switch (current_state_) { case INITIAL_APPROACH: prev_path_ = initial(plan_request); @@ -46,8 +54,8 @@ Trajectory LineKickPathPlanner::plan(const PlanRequest& plan_request) { break; } prev_path_.stamp(RJ::now()); - has_created_plan = true; return prev_path_; + // } } Trajectory LineKickPathPlanner::initial(const PlanRequest& plan_request) { diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index 2d97c3d851c..aa16db35643 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -140,8 +140,7 @@ std::optional Offense::state_to_task(RobotIntent intent) { return intent; } else if (current_state_ == SHOOTING) { rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc(); - rj_geometry::Point scoring_point = - their_goal_pos + field_dimensions_.goal_width() * 3.0 / 8.0; + rj_geometry::Point scoring_point = their_goal_pos + field_dimensions_.goal_width() * 3.0 / 8.0; planning::LinearMotionInstant target{scoring_point}; auto line_kick_cmd = planning::MotionCommand{"line_kick", target}; intent.motion_command = line_kick_cmd; From 035bae35c79aa62905c98de01dc2fd846b02015e Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Sun, 21 Jan 2024 21:21:07 -0500 Subject: [PATCH 2/8] Fix Code Style On rewrite-linekicker (#2165) automated style fixes Co-authored-by: petergarud --- soccer/src/soccer/strategy/agent/position/offense.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index aa16db35643..2d97c3d851c 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -140,7 +140,8 @@ std::optional Offense::state_to_task(RobotIntent intent) { return intent; } else if (current_state_ == SHOOTING) { rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc(); - rj_geometry::Point scoring_point = their_goal_pos + field_dimensions_.goal_width() * 3.0 / 8.0; + rj_geometry::Point scoring_point = + their_goal_pos + field_dimensions_.goal_width() * 3.0 / 8.0; planning::LinearMotionInstant target{scoring_point}; auto line_kick_cmd = planning::MotionCommand{"line_kick", target}; intent.motion_command = line_kick_cmd; From b06053e35867511ead7c80241cdcc04a30cbc2ee Mon Sep 17 00:00:00 2001 From: petergarud Date: Tue, 23 Jan 2024 00:37:40 +0000 Subject: [PATCH 3/8] calcualtes best shot by finding path furthests from enemy --- .../strategy/agent/position/offense.cpp | 46 +++++++++++++++++-- .../strategy/agent/position/offense.hpp | 10 ++++ 2 files changed, 52 insertions(+), 4 deletions(-) diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index 2d97c3d851c..9d8292bd140 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -139,10 +139,7 @@ std::optional Offense::state_to_task(RobotIntent intent) { intent.dribbler_speed = 255.0; return intent; } else if (current_state_ == SHOOTING) { - rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc(); - rj_geometry::Point scoring_point = - their_goal_pos + field_dimensions_.goal_width() * 3.0 / 8.0; - planning::LinearMotionInstant target{scoring_point}; + planning::LinearMotionInstant target{calculate_best_shot()}; auto line_kick_cmd = planning::MotionCommand{"line_kick", target}; intent.motion_command = line_kick_cmd; intent.shoot_mode = RobotIntent::ShootMode::KICK; @@ -416,4 +413,45 @@ void Offense::derived_acknowledge_ball_in_transit() { chasing_ball = false; } +rj_geometry::Point Offense::calculate_best_shot() { + + // Goal location + rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc(); + double goal_width = field_dimensions_.goal_width(); // 1.0 meters + + // Ball location + rj_geometry::Point ball_position = this->last_world_state_->ball.position; + + rj_geometry::Point best_shot = their_goal_pos; + double best_distance = -1.0; + rj_geometry::Point increment(0.05, 0); + rj_geometry::Point curr_point = their_goal_pos - rj_geometry::Point(goal_width / 2.0, 0) + increment; + for (int i = 0; i < 19; i++) { + double distance = distance_from_their_robots(ball_position, curr_point); + if (distance > best_distance) { + best_distance = distance; + best_shot = curr_point; + } + curr_point = curr_point + increment; + } + return best_shot; +} + +double Offense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point head) { + rj_geometry::Point vec = head - tail; + auto their_robots = this->last_world_state_->their_robots; + double min_distance = -1.0; + for (auto enemy : their_robots) { + rj_geometry::Point enemy_vec = enemy.pose.position() - tail; + enemy_vec = enemy_vec - (enemy_vec.dot(vec)/vec.dot(vec)) * vec; + double distance = enemy_vec.mag(); + if (min_distance == -1.0) { + min_distance = distance; + } else if(distance < min_distance) { + min_distance = distance; + } + } + return min_distance; +} + } // namespace strategy diff --git a/soccer/src/soccer/strategy/agent/position/offense.hpp b/soccer/src/soccer/strategy/agent/position/offense.hpp index 66b60bea296..1b12a81af41 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.hpp +++ b/soccer/src/soccer/strategy/agent/position/offense.hpp @@ -114,6 +114,16 @@ class Offense : public Position { * status */ communication::Acknowledge receive_reset_scorer_request(); + + /** + * @brief Calcualtes the best location for a shot + */ + rj_geometry::Point calculate_best_shot(); + + /** + * @brief Calculates the distance of vector from other team's closest robot + */ + double distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point heaad); }; } // namespace strategy From bc303c9d825a727b56fcd91e4eb434b6dfe363ed Mon Sep 17 00:00:00 2001 From: petergarud Date: Wed, 24 Jan 2024 01:29:57 +0000 Subject: [PATCH 4/8] checked for angle, not distance and disregarded enemys behind trajectory --- .../strategy/agent/position/offense.cpp | 26 ++++++++++++------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index 9d8292bd140..d748a0a9fe5 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -416,7 +416,7 @@ void Offense::derived_acknowledge_ball_in_transit() { rj_geometry::Point Offense::calculate_best_shot() { // Goal location - rj_geometry::Point their_goal_pos = field_dimensions_.their_goal_loc(); + rj_geometry::Point their_goal_pos = field_dimensions_.our_goal_loc(); double goal_width = field_dimensions_.goal_width(); // 1.0 meters // Ball location @@ -439,19 +439,27 @@ rj_geometry::Point Offense::calculate_best_shot() { double Offense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point head) { rj_geometry::Point vec = head - tail; - auto their_robots = this->last_world_state_->their_robots; - double min_distance = -1.0; + auto their_robots = this->last_world_state_->our_robots; + double min_angle = -0.5; for (auto enemy : their_robots) { rj_geometry::Point enemy_vec = enemy.pose.position() - tail; - enemy_vec = enemy_vec - (enemy_vec.dot(vec)/vec.dot(vec)) * vec; + if (enemy_vec.dot(vec) < 0 ) { + continue; + } + auto projection = (enemy_vec.dot(vec)/vec.dot(vec)); + enemy_vec = enemy_vec - (projection) * vec; double distance = enemy_vec.mag(); - if (min_distance == -1.0) { - min_distance = distance; - } else if(distance < min_distance) { - min_distance = distance; + if (distance < (kRobotRadius + kBallRadius)) { + return -1.0; + } + double angle = distance / projection; + if (min_angle < 0) { + min_angle = angle; + } else if(angle < min_angle) { + min_angle = angle; } } - return min_distance; + return min_angle; } } // namespace strategy From b56bd3e4e108a1dc9f8068ec7eddcd2420303660 Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Mon, 29 Jan 2024 16:38:50 -0500 Subject: [PATCH 5/8] Fix Code Style On best-shot (#2171) automated style fixes Co-authored-by: sid-parikh --- .../src/soccer/strategy/agent/position/offense.cpp | 14 +++++++------- .../src/soccer/strategy/agent/position/offense.hpp | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index d748a0a9fe5..6a4545d6ce2 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -414,10 +414,9 @@ void Offense::derived_acknowledge_ball_in_transit() { } rj_geometry::Point Offense::calculate_best_shot() { - // Goal location rj_geometry::Point their_goal_pos = field_dimensions_.our_goal_loc(); - double goal_width = field_dimensions_.goal_width(); // 1.0 meters + double goal_width = field_dimensions_.goal_width(); // 1.0 meters // Ball location rj_geometry::Point ball_position = this->last_world_state_->ball.position; @@ -425,7 +424,8 @@ rj_geometry::Point Offense::calculate_best_shot() { rj_geometry::Point best_shot = their_goal_pos; double best_distance = -1.0; rj_geometry::Point increment(0.05, 0); - rj_geometry::Point curr_point = their_goal_pos - rj_geometry::Point(goal_width / 2.0, 0) + increment; + rj_geometry::Point curr_point = + their_goal_pos - rj_geometry::Point(goal_width / 2.0, 0) + increment; for (int i = 0; i < 19; i++) { double distance = distance_from_their_robots(ball_position, curr_point); if (distance > best_distance) { @@ -443,11 +443,11 @@ double Offense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry: double min_angle = -0.5; for (auto enemy : their_robots) { rj_geometry::Point enemy_vec = enemy.pose.position() - tail; - if (enemy_vec.dot(vec) < 0 ) { + if (enemy_vec.dot(vec) < 0) { continue; } - auto projection = (enemy_vec.dot(vec)/vec.dot(vec)); - enemy_vec = enemy_vec - (projection) * vec; + auto projection = (enemy_vec.dot(vec) / vec.dot(vec)); + enemy_vec = enemy_vec - (projection)*vec; double distance = enemy_vec.mag(); if (distance < (kRobotRadius + kBallRadius)) { return -1.0; @@ -455,7 +455,7 @@ double Offense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry: double angle = distance / projection; if (min_angle < 0) { min_angle = angle; - } else if(angle < min_angle) { + } else if (angle < min_angle) { min_angle = angle; } } diff --git a/soccer/src/soccer/strategy/agent/position/offense.hpp b/soccer/src/soccer/strategy/agent/position/offense.hpp index 1b12a81af41..dd5ae819c75 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.hpp +++ b/soccer/src/soccer/strategy/agent/position/offense.hpp @@ -117,12 +117,12 @@ class Offense : public Position { /** * @brief Calcualtes the best location for a shot - */ + */ rj_geometry::Point calculate_best_shot(); /** * @brief Calculates the distance of vector from other team's closest robot - */ + */ double distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point heaad); }; From 6a80380bc08bc24d0e0c136ca46c4cf2c897fcc8 Mon Sep 17 00:00:00 2001 From: Sid Parikh Date: Thu, 1 Feb 2024 18:15:44 +0000 Subject: [PATCH 6/8] clean up line kick --- .../planner/line_kick_path_planner.cpp | 54 +++++++---------- .../planner/line_kick_path_planner.hpp | 58 +++++++++++-------- 2 files changed, 55 insertions(+), 57 deletions(-) diff --git a/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp b/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp index ad25d67a2ac..032c4ba75bf 100644 --- a/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp +++ b/soccer/src/soccer/planning/planner/line_kick_path_planner.cpp @@ -13,6 +13,9 @@ using namespace rj_geometry; namespace planning { Trajectory LineKickPathPlanner::plan(const PlanRequest& plan_request) { + // If we are not allowed to touch the ball, this planner always fails + // This is preferred to simply ending the planner because it is possible (likely) + // that strategy re-requests the same planner anyway. if (plan_request.play_state == PlayState::halt() || plan_request.play_state == PlayState::stop()) { return Trajectory{}; @@ -29,22 +32,10 @@ Trajectory LineKickPathPlanner::plan(const PlanRequest& plan_request) { // // e.g. new_avg_vel = (0.8 * avg_vel) + (0.2 * new_vel) // - // TODO(Kevin): make this gain a ROS param like collect average_ball_vel_ = apply_low_pass_filter(average_ball_vel_, ball.velocity, 0.8); } - // ShapeSet static_obstacles; - // std::vector dynamic_obstacles; - // fill_obstacles(plan_request, &static_obstacles, &dynamic_obstacles, false, nullptr); - - // auto obstacles_with_ball = static_obstacles; - // const RJ::Time cur_time = start_instant.stamp; - // obstacles_with_ball.add( - // make_shared(ball.predict_at(cur_time).position, ball_avoid_distance)); - - // // only plan line kick if not is_done - // if (!this->is_done()) { - state_transition(ball, plan_request.start); + process_state_transition(); switch (current_state_) { case INITIAL_APPROACH: prev_path_ = initial(plan_request); @@ -55,61 +46,56 @@ Trajectory LineKickPathPlanner::plan(const PlanRequest& plan_request) { } prev_path_.stamp(RJ::now()); return prev_path_; - // } } Trajectory LineKickPathPlanner::initial(const PlanRequest& plan_request) { // Getting ball info const BallState& ball = plan_request.world_state->ball; - // Creating a modified plan_request to send to PathTargetPlanner - PlanRequest modified_request = plan_request; - - // Where to navigate to + // Distance to stay away from the ball auto distance_from_ball = kBallRadius + kRobotRadius + kAvoidBallBy; + // In case the ball is (slowly) moving auto ball_position = ball.predict_at(RJ::now() + RJ::Seconds{kPredictIn}).position; + // Along the vector from the goal to ball auto goal_to_ball = (plan_request.motion_command.target.position - ball_position); auto offset_from_ball = distance_from_ball * goal_to_ball.normalized(); - // Updating the motion command + // Create an updated MotionCommand and forward to PathTargetPathPlaner + PlanRequest modified_request = plan_request; + LinearMotionInstant target{ball_position - offset_from_ball}; MotionCommand modified_command{"path_target", target, FacePoint{plan_request.motion_command.target.position}}; modified_request.motion_command = modified_command; - // Getting the new path from PathTargetPlanner - Trajectory path = path_target_.plan(modified_request); - - return path; + return path_target_.plan(modified_request); } Trajectory LineKickPathPlanner::final(const PlanRequest& plan_request) { - // remove ball from obstacles not needed? - const BallState& ball = plan_request.world_state->ball; - // Creating a modified plan_request to send to PathTargetPlanner - PlanRequest modified_request = plan_request; - - // velocity + // Velocity is the speed (parameter) times the unit vector in the correct direction auto goal_to_ball = (plan_request.motion_command.target.position - ball.position); auto vel = goal_to_ball.normalized() * kFinalRobotSpeed; + // Create an updated MotionCommand and forward to PathTargetPathPlaner + PlanRequest modified_request = plan_request; + LinearMotionInstant target{ball.position, vel}; + MotionCommand modified_command{"path_target", target, - FacePoint{plan_request.motion_command.target.position}, true}; + FacePoint{plan_request.motion_command.target.position}}; modified_request.motion_command = modified_command; - // Getting the new path from PathTargetPlanner - Trajectory path = path_target_.plan(modified_request); - - return path; + return path_target_.plan(modified_request); } void LineKickPathPlanner::process_state_transition() { + // Let PathTarget decide when the first stage is done + // Possible problem: can PathTarget get stuck and loop infinitely? if (current_state_ == INITIAL_APPROACH && (path_target_.is_done())) { current_state_ = FINAL_APPROACH; } diff --git a/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp b/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp index 0e451c79764..ac2d0c5eab4 100644 --- a/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp +++ b/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp @@ -7,19 +7,22 @@ #include "planning/planner/path_target_path_planner.hpp" #include "planning/trajectory.hpp" -class Configuration; -class ConfigDouble; - namespace planning { /** * PathPlanner which plans a path to line kick a ball. - * Uses the System State object to get the position of the ball - * and predict its Path. It chooses the closest intersection point - * with the ball Path it can reach in time and plans a Path so the - * ball and robot intersect at the same time. + * It takes the ball's current trajectory and plans a path for the robot + * to intersect with the ball. + * + * It is in two stages. The first stage drives up to the ball, trying to avoid + * accidentally tapping it out of place. The second stage drives directly + * into the ball, hopefully kicking it if the hardware has been instructed + * to kick. * - * TODO(Kyle): Overhaul this entire planner. It's sketchy right now. + * Because of the two-stage system, this planner is *stateful*. It ought + * not to be destructed and re-constructed during a single execution; + * the best approach is to call plan() on each tick. + * However, it also shouldn't *completely* break if it is reset. * * Params taken from MotionCommand: * target.position - planner will kick to this point @@ -31,40 +34,49 @@ class LineKickPathPlanner : public PathPlanner { void reset() override { prev_path_ = {}; - target_kick_pos_ = std::nullopt; current_state_ = INITIAL_APPROACH; average_ball_vel_initialized_ = false; - has_created_plan = false; } + [[nodiscard]] bool is_done() const override; private: enum State { INITIAL_APPROACH, FINAL_APPROACH }; - State current_state_ = INITIAL_APPROACH; + + State current_state_{INITIAL_APPROACH}; + PathTargetPathPlanner path_target_{}; CollectPathPlanner collect_planner_{}; Trajectory prev_path_; // These constants could be tuned more - static constexpr double kIsDoneBallVel = 1.5; - static constexpr double kFinalRobotSpeed = 1.0; - static constexpr double kPredictIn = 0.5; // seconds - static constexpr double kAvoidBallBy = 0.05; + static constexpr double kIsDoneBallVel{1.5}; + static constexpr double kFinalRobotSpeed{1.0}; + static constexpr double kPredictIn{0.5}; // seconds + static constexpr double kAvoidBallBy{0.05}; + static constexpr double kLowPassFilterGain{0.2}; rj_geometry::Point average_ball_vel_; bool average_ball_vel_initialized_ = false; - bool has_created_plan = false; - std::optional target_kick_pos_; - // Trajectory initial(BallState ball, MotionCommand command, RobotInstant start_instant, - // ShapeSet static_obstacles, std::vector dynamic_obstacles); + /** + * Returns the trajectory during the initial stage. + * Uses PathTargetPathPlanner to draw a path to the spot to kick from. + * Avoids the ball + */ Trajectory initial(const PlanRequest& plan_request); + + /** + * Returns the trajectory during the final stage. + * Uses PathTargetPathPlanner to draw a path directly into the ball. + * Tries to hit the ball with the mouth of the robot. + */ Trajectory final(const PlanRequest& plan_request); - // Trajectory final(BallState ball, MotionCommand command, RobotInstant start_instant, ShapeSet - // static_obstacles, std::vector dynamic_obstacles); - void process_state_transition(); - // PlayState::State current_state_; + /** + * Decides if the intial approach is complete and updates internal state as necessary. + */ + void process_state_transition(); }; } // namespace planning From ca2b2147283479156dd0cbb0276c80bb6e941e9f Mon Sep 17 00:00:00 2001 From: Sid Parikh Date: Thu, 1 Feb 2024 18:16:08 +0000 Subject: [PATCH 7/8] fix offense ODR violation --- .../strategy/agent/position/offense.cpp | 25 ------------------- .../strategy/agent/position/offense.hpp | 2 -- 2 files changed, 27 deletions(-) diff --git a/soccer/src/soccer/strategy/agent/position/offense.cpp b/soccer/src/soccer/strategy/agent/position/offense.cpp index 6a4545d6ce2..3c1a6ef680c 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.cpp +++ b/soccer/src/soccer/strategy/agent/position/offense.cpp @@ -437,29 +437,4 @@ rj_geometry::Point Offense::calculate_best_shot() { return best_shot; } -double Offense::distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point head) { - rj_geometry::Point vec = head - tail; - auto their_robots = this->last_world_state_->our_robots; - double min_angle = -0.5; - for (auto enemy : their_robots) { - rj_geometry::Point enemy_vec = enemy.pose.position() - tail; - if (enemy_vec.dot(vec) < 0) { - continue; - } - auto projection = (enemy_vec.dot(vec) / vec.dot(vec)); - enemy_vec = enemy_vec - (projection)*vec; - double distance = enemy_vec.mag(); - if (distance < (kRobotRadius + kBallRadius)) { - return -1.0; - } - double angle = distance / projection; - if (min_angle < 0) { - min_angle = angle; - } else if (angle < min_angle) { - min_angle = angle; - } - } - return min_angle; -} - } // namespace strategy diff --git a/soccer/src/soccer/strategy/agent/position/offense.hpp b/soccer/src/soccer/strategy/agent/position/offense.hpp index dd5ae819c75..705890dc482 100644 --- a/soccer/src/soccer/strategy/agent/position/offense.hpp +++ b/soccer/src/soccer/strategy/agent/position/offense.hpp @@ -71,8 +71,6 @@ class Offense : public Position { bool has_open_shot(); - double distance_from_their_robots(rj_geometry::Point tail, rj_geometry::Point head); - /** * @brief Send request to the other robots to see if this robot should be the scorer * From bbc3fd734064424c463dea5250487df62dd3503a Mon Sep 17 00:00:00 2001 From: "github-actions[bot]" <41898282+github-actions[bot]@users.noreply.github.com> Date: Thu, 1 Feb 2024 13:18:06 -0500 Subject: [PATCH 8/8] Fix Code Style On best-shot (#2183) automated style fixes Co-authored-by: sid-parikh --- .../planner/line_kick_path_planner.hpp | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp b/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp index ac2d0c5eab4..900c08b88d0 100644 --- a/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp +++ b/soccer/src/soccer/planning/planner/line_kick_path_planner.hpp @@ -20,7 +20,7 @@ namespace planning { * to kick. * * Because of the two-stage system, this planner is *stateful*. It ought - * not to be destructed and re-constructed during a single execution; + * not to be destructed and re-constructed during a single execution; * the best approach is to call plan() on each tick. * However, it also shouldn't *completely* break if it is reset. * @@ -60,22 +60,22 @@ class LineKickPathPlanner : public PathPlanner { bool average_ball_vel_initialized_ = false; /** - * Returns the trajectory during the initial stage. - * Uses PathTargetPathPlanner to draw a path to the spot to kick from. - * Avoids the ball - */ + * Returns the trajectory during the initial stage. + * Uses PathTargetPathPlanner to draw a path to the spot to kick from. + * Avoids the ball + */ Trajectory initial(const PlanRequest& plan_request); /** - * Returns the trajectory during the final stage. - * Uses PathTargetPathPlanner to draw a path directly into the ball. - * Tries to hit the ball with the mouth of the robot. - */ + * Returns the trajectory during the final stage. + * Uses PathTargetPathPlanner to draw a path directly into the ball. + * Tries to hit the ball with the mouth of the robot. + */ Trajectory final(const PlanRequest& plan_request); /** - * Decides if the intial approach is complete and updates internal state as necessary. - */ + * Decides if the intial approach is complete and updates internal state as necessary. + */ void process_state_transition(); };