diff --git a/config/plays.txt b/config/plays.txt index 1c62931130..f57a116719 100644 --- a/config/plays.txt +++ b/config/plays.txt @@ -8,4 +8,5 @@ penalty_defense.PenaltyDefense() penalty_offense.PenaltyOffense() test_motion_planning.OneRobot() test_motion_planning.AllBots() +test_motion_planning.KickBall() None diff --git a/rj_common/include/rj_common/utils.hpp b/rj_common/include/rj_common/utils.hpp index 37491aac5e..55ec1ba672 100644 --- a/rj_common/include/rj_common/utils.hpp +++ b/rj_common/include/rj_common/utils.hpp @@ -21,6 +21,21 @@ static inline T fix_angle_radians(T a) { return remainder(a, 2 * M_PI); } +/* + * @brief Approximate moving average with first-order low pass filter. + * + * @details For those without a digital signal processing background, think of + * it as giving small weights to new estimates compared to the existing belief. + * For example, to approximate the avg velocity, with a gain of 0.8, we can do: + * new_avg_vel = (0.8 * old_avg_vel) + (0.2 * most_recent_vel) + * every time a new velocity comes in. This protects us from noisy velocity + * readings while also updating the average as it changes. + * + * @param old_value current value of moving average + * @param new_value new value to add to moving average + * @param gain resistance to noise (higher = more weight to old_value) + * @return new moving average estimate + */ template inline T apply_low_pass_filter(const T& old_value, const T& new_value, double gain) { return gain * new_value + (1 - gain) * old_value; diff --git a/rj_gameplay/rj_gameplay/play/test_motion_planning.py b/rj_gameplay/rj_gameplay/play/test_motion_planning.py index 3c21ead69c..0ce7954b95 100644 --- a/rj_gameplay/rj_gameplay/play/test_motion_planning.py +++ b/rj_gameplay/rj_gameplay/play/test_motion_planning.py @@ -8,7 +8,7 @@ import stp.role.cost from rj_msgs.msg import RobotIntent -from rj_gameplay.skill import move +from rj_gameplay.skill import move, pivot_kick class State(Enum): @@ -159,3 +159,44 @@ def tick( intents[i] = self._move_skills[i].tick(world_state) return intents + + +class KickBall(stp.play.Play): + """ + Make robot 0 capture, then kick the ball. + + Directly overrides the STP architecture to send RI to gameplay. + """ + + def __init__(self): + super().__init__() + self._state = "capturing" + self.capture_skill = None + self.pivot_kick_skill = None + + self.robot_id = 0 + self.robot = None + + def tick( + self, + world_state: stp.rc.WorldState, + ) -> List[RobotIntent]: + + self.robot = world_state.our_robots[self.robot_id] + intents = [None for _ in range(16)] + my_robot_intent = None + + # None on INIT and state changes + if self.pivot_kick_skill is None: + self.pivot_kick_skill = pivot_kick.PivotKick( + robot=self.robot, + target_point=np.array([0.0, 6.0]), + chip=True, + kick_speed=5.0, + ) + else: + my_robot_intent = self.pivot_kick_skill.tick(world_state) + + intents[self.robot_id] = my_robot_intent + + return intents diff --git a/rj_gameplay/rj_gameplay/role/seeker.py b/rj_gameplay/rj_gameplay/role/seeker.py index 5d8aa664ea..e2a24a0a15 100644 --- a/rj_gameplay/rj_gameplay/role/seeker.py +++ b/rj_gameplay/rj_gameplay/role/seeker.py @@ -32,7 +32,9 @@ def get_open_point(self, world_state, region: List, centroid) -> np.ndarray: # line-of-sight calculations # (LOS is maximized by making dot product of angle between unit vectors as close to 0 as possible) ball_dir = lambda pos: pos - world_state.ball.pos - ball_dir_norm = lambda pos: ball_dir(pos) / np.linalg.norm(ball_dir(pos)) + ball_dir_norm = lambda pos: ball_dir(pos) / ( + 1e-9 + np.linalg.norm(ball_dir(pos)) + ) opps_to_ball = [ ball_dir_norm(opp_robot.pose[0:2]) for opp_robot in world_state.their_robots ] diff --git a/rj_gameplay/rj_gameplay/skill/capture.py b/rj_gameplay/rj_gameplay/skill/capture.py index 67e02bb8c0..096ef00913 100644 --- a/rj_gameplay/rj_gameplay/skill/capture.py +++ b/rj_gameplay/rj_gameplay/skill/capture.py @@ -1,20 +1,14 @@ -from abc import ABC, abstractmethod - -import rj_gameplay.eval as eval import argparse -import py_trees import sys import time -from rj_msgs.msg import RobotIntent, CollectMotionCommand +from typing import Optional -import stp.skill as skill -import stp.role as role +import numpy as np import stp.action as action import stp.rc as rc -from typing import Optional -import numpy as np - -from stp.utils.constants import RobotConstants +import stp.skill as skill +from rj_msgs.msg import CollectMotionCommand, RobotIntent +from stp.utils.constants import BallConstants, RobotConstants class Capture(skill.Skill): @@ -46,8 +40,10 @@ def is_done(self, world_state) -> bool: dist_to_ball = np.linalg.norm(robot_pos - ball_pos) - ball_slow = ball_speed < 1.0 - ball_close = dist_to_ball < RobotConstants.RADIUS * 1.3 + ball_slow = ball_speed < 0.05 + ball_close = ( + dist_to_ball - (RobotConstants.RADIUS + BallConstants.RADIUS) < 0.03 + ) return ball_slow and ball_close diff --git a/rj_gameplay/rj_gameplay/skill/line_kick.py b/rj_gameplay/rj_gameplay/skill/line_kick.py index b4fd643597..7a1f2457a9 100644 --- a/rj_gameplay/rj_gameplay/skill/line_kick.py +++ b/rj_gameplay/rj_gameplay/skill/line_kick.py @@ -76,9 +76,9 @@ def is_done(self, world_state: rc.WorldState): KICK_DOT_THRESHOLD = 0.4 KICK_BALL_SPEED_THRESHOLD = 0.9 - # TODO: make pivot kick and line kick inherit from some common kick superclass to make this cleaner if self.robot is None: return False + ball_vel_unit = world_state.ball.vel / np.linalg.norm(world_state.ball.vel) heading_angle = world_state.our_robots[self.robot.id].pose[2] heading_vect = np.array([np.cos(heading_angle), np.sin(heading_angle)]) diff --git a/rj_gameplay/rj_gameplay/skill/move.py b/rj_gameplay/rj_gameplay/skill/move.py index 5d31dc28cc..1571d399a2 100644 --- a/rj_gameplay/rj_gameplay/skill/move.py +++ b/rj_gameplay/rj_gameplay/skill/move.py @@ -61,21 +61,22 @@ def tick(self, world_state: rc.WorldState) -> RobotIntent: return intent def is_done(self, world_state: rc.WorldState) -> bool: - threshold = 0.3 + position_tolerance = 1e-2 + velocity_tolerance = 1e-1 if self.robot.id is None or world_state is None: return False - elif ( - math.sqrt( - (world_state.our_robots[self.robot.id].pose[0] - self.target_point[0]) - ** 2 - + (world_state.our_robots[self.robot.id].pose[1] - self.target_point[1]) - ** 2 - ) - < threshold - ): - return True - else: - return False + + # only linear for now (so this is technically not pose, which + # includes angular position) + robot_pt = world_state.our_robots[self.robot.id].pose[:2] + goal_pt = self.target_point + robot_vel = world_state.our_robots[self.robot.id].twist[:2] + goal_vel = self.target_vel + + return ( + np.linalg.norm(robot_pt - goal_pt) < position_tolerance + and np.linalg.norm(robot_vel - goal_vel) < velocity_tolerance + ) def __str__(self): ignore_ball_str = ", ignoring ball" if self.ignore_ball else "" diff --git a/rj_gameplay/rj_gameplay/skill/pivot.py b/rj_gameplay/rj_gameplay/skill/pivot.py index 4abb1983cb..e4e83fc598 100644 --- a/rj_gameplay/rj_gameplay/skill/pivot.py +++ b/rj_gameplay/rj_gameplay/skill/pivot.py @@ -16,7 +16,7 @@ def __init__( pivot_point: np.ndarray = None, target_point: np.ndarray = None, dribble_speed: float = 1.0, - threshold: float = 0.2, + threshold: float = 0.05, priority: int = 1, ): self.robot = robot @@ -48,7 +48,6 @@ def is_done(self, world_state: rc.WorldState) -> bool: if self.robot is None: return False angle_threshold = self.threshold - angle_threshold = 0.05 stopped_threshold = ( 5 * self.threshold ) # We don't _really_ care about this when we're kicking, if not for latency diff --git a/rj_gameplay/rj_gameplay/skill/receive.py b/rj_gameplay/rj_gameplay/skill/receive.py index 6ddc39f727..35029d10d2 100644 --- a/rj_gameplay/rj_gameplay/skill/receive.py +++ b/rj_gameplay/rj_gameplay/skill/receive.py @@ -1,19 +1,14 @@ -from abc import ABC, abstractmethod - -import rj_gameplay.eval as eval import argparse -import py_trees import sys import time -import numpy as np from typing import Optional -import stp.skill as skill -import stp.role as role -from rj_gameplay.skill import settle, capture -from rj_msgs.msg import RobotIntent, SettleMotionCommand import stp.rc as rc +import stp.skill as skill from rj_msgs import msg +from rj_msgs.msg import RobotIntent + +from rj_gameplay.skill import capture, settle class Receive(skill.Skill): @@ -38,7 +33,6 @@ def tick(self, world_state: rc.WorldState) -> RobotIntent: return self.settle.tick(world_state) def is_done(self, world_state: rc.WorldState) -> bool: - return self.capture.is_done(world_state) def __str__(self): diff --git a/rj_geometry/include/rj_geometry/point.hpp b/rj_geometry/include/rj_geometry/point.hpp index 95d26947a2..7f7bbb1311 100644 --- a/rj_geometry/include/rj_geometry/point.hpp +++ b/rj_geometry/include/rj_geometry/point.hpp @@ -1,14 +1,16 @@ #pragma once -#include +#include +#include +#include #include #include #include -#include + +#include #include -#include -#include +#include namespace rj_geometry { @@ -375,7 +377,29 @@ class Point { return acos(std::max(std::min(angle, 1.0), -1.0)); } - [[nodiscard]] bool nearly_equals(Point other) const; + /* + * @brief Return true if this point is close enough to another Point. + * + * @param other Point to compare with this point + * @tolerance maximum allowed difference in x/y coord to be considered equal + * @return true if x/y of this Point are both less than tolerance away from other + */ + [[nodiscard]] bool nearly_equals(Point other, double tolerance = 1e-4) const { + return nearly_equal(static_cast(x()), static_cast(other.x()), tolerance) && + nearly_equal(static_cast(y()), static_cast(other.y()), tolerance); + } + + /* + * @brief Return true if points a and b are close enough to each other. + * + * @param a Point a + * @param b Point b + * @tolerance maximum allowed difference in x/y coord to be considered equal + * @return true if x/y of Point a are both less than tolerance away from Point b + */ + static bool nearly_equals(const Point& a, const Point& b, double tolerance = 1e-4) { + return a.nearly_equals(b, tolerance); + } [[nodiscard]] std::string to_string() const { std::stringstream str; diff --git a/rj_geometry/include/rj_geometry/util.hpp b/rj_geometry/include/rj_geometry/util.hpp index 5c61cc1532..4a213cd71c 100644 --- a/rj_geometry/include/rj_geometry/util.hpp +++ b/rj_geometry/include/rj_geometry/util.hpp @@ -34,8 +34,14 @@ static inline T sign(T f) { } // TODO(1485): Make this smaller once we figure out why test are failing in O3. -// static const float FLOAT_EPSILON = 0.00001; -static const float kFloatEpsilon = 1e-4; -static bool nearly_equal(float a, float b) { - return std::fabs(a - b) < kFloatEpsilon; +/* + * @brief Return true if doubles a and b are close enough to each other. + * + * @param a double a + * @param b double b + * @tolerance maximum allowed difference in x/y coord to be considered equal + * @return true if x/y of double a are both less than tolerance away from double b + */ +static bool nearly_equal(double a, double b, double tolerance = 1e-4) { + return std::fabs(a - b) < tolerance; } diff --git a/rj_geometry/src/point.cpp b/rj_geometry/src/point.cpp index eb9eb24c7d..4860bbf38f 100644 --- a/rj_geometry/src/point.cpp +++ b/rj_geometry/src/point.cpp @@ -2,8 +2,6 @@ #include namespace rj_geometry { -bool Point::nearly_equals(Point other) const { - return nearly_equal(static_cast(x()), static_cast(other.x())) && - nearly_equal(static_cast(y()), static_cast(other.y())); -} +// TODO(Kevin): delete this file +// did not do it yet because build system make me sad } // namespace rj_geometry diff --git a/rj_geometry/testing/point_test.cpp b/rj_geometry/testing/point_test.cpp index 01e5c9f620..c5363b87c8 100644 --- a/rj_geometry/testing/point_test.cpp +++ b/rj_geometry/testing/point_test.cpp @@ -203,14 +203,17 @@ TEST(Point, normalized) { } TEST(Point, nearly_equals) { - EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0, 5))); - EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0 - kFloatEpsilon / 2, 5 + kFloatEpsilon / 2))); - EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0 + kFloatEpsilon / 2, 5 - kFloatEpsilon / 2))); - - EXPECT_FALSE( - Point(0, 5).nearly_equals(Point(0 - kFloatEpsilon * 1.1, 5 + kFloatEpsilon * 1.1))); - EXPECT_FALSE( - Point(0, 5).nearly_equals(Point(0 + kFloatEpsilon * 1.1, 5 - kFloatEpsilon * 1.1))); + double test_tolerance = 1e-4; + EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0, 5), test_tolerance)); + EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0 - test_tolerance / 2, 5 + test_tolerance / 2), + test_tolerance)); + EXPECT_TRUE(Point(0, 5).nearly_equals(Point(0 + test_tolerance / 2, 5 - test_tolerance / 2), + test_tolerance)); + + EXPECT_FALSE(Point(0, 5).nearly_equals( + Point(0 - test_tolerance * 1.1, 5 + test_tolerance * 1.1), test_tolerance)); + EXPECT_FALSE(Point(0, 5).nearly_equals( + Point(0 + test_tolerance * 1.1, 5 - test_tolerance * 1.1), test_tolerance)); } // TODO(ashaw596) Add tests for angle_to and angle_between once those changes are // merged diff --git a/soccer/src/soccer/planning/instant.hpp b/soccer/src/soccer/planning/instant.hpp index b9f8e1962a..1f6c0714e8 100644 --- a/soccer/src/soccer/planning/instant.hpp +++ b/soccer/src/soccer/planning/instant.hpp @@ -28,6 +28,22 @@ struct LinearMotionInstant { rj_geometry::Point position; rj_geometry::Point velocity; + /** + * @brief Return true if LinearMotionInstant a and b are nearly equal. + * + * @param a LinearMotionInstant a + * @param b LinearMotionInstant b + * @param position_tolerance tolerance on position component of LinearMotionInstant + * @param velocity_tolerance tolerance on velocity component of LinearMotionInstant + * @return True if a and b are within position_tolerance of each other AND velocity_tolerance of + * each other + */ + static bool nearly_equals(const LinearMotionInstant& a, const LinearMotionInstant& b, + double position_tolerance = 1e-4, double velocity_tolerance = 1e-4) { + return rj_geometry::Point::nearly_equals(a.position, b.position, position_tolerance) && + rj_geometry::Point::nearly_equals(a.velocity, b.velocity, velocity_tolerance); + } + friend std::ostream& operator<<(std::ostream& stream, const LinearMotionInstant& instant) { return stream << "LinearMotionInstant(position=" << instant.position diff --git a/soccer/src/soccer/planning/planner/collect_planner.cpp b/soccer/src/soccer/planning/planner/collect_planner.cpp index af281d6f8a..dc9ca16109 100644 --- a/soccer/src/soccer/planning/planner/collect_planner.cpp +++ b/soccer/src/soccer/planning/planner/collect_planner.cpp @@ -77,12 +77,18 @@ Trajectory CollectPlanner::plan(const PlanRequest& plan_request) { } // Initialize the filter to the ball velocity so there's less ramp up + // TODO(Kevin): add an issue # here + // TODO: when ball velocity = 0 but ball is not in mouth (due to bouncing), this fails if (!average_ball_vel_initialized_) { average_ball_vel_ = ball.velocity; average_ball_vel_initialized_ = true; } else { - average_ball_vel_ = collect::PARAM_target_point_lowpass_gain * average_ball_vel_ + - (1 - collect::PARAM_target_point_lowpass_gain) * ball.velocity; + // Add the newest ball velocity measurement to the average velocity + // estimate, but downweight the new value heavily + // + // e.g. new_avg_vel = (0.8 * avg_vel) + (0.2 * new_vel) + average_ball_vel_ = apply_low_pass_filter(average_ball_vel_, ball.velocity, + collect::PARAM_target_point_lowpass_gain); } // Approach direction is the direction we move towards the ball and through @@ -330,6 +336,10 @@ Trajectory CollectPlanner::control(const PlanRequest& plan_request, RobotInstant .norm(); LinearMotionInstant target{target_pos}; + // save for is_done() + cached_robot_pos_ = start.position(); + cached_ball_pos_ = ball.position; + // Try to use the RRTPlanner to generate the path first // It reaches the target better for some reason std::vector start_end_points{start.position(), target.position}; @@ -394,4 +404,25 @@ void CollectPlanner::reset() { path_coarse_target_initialized_ = false; } +bool CollectPlanner::is_done() const { + // FSM: CourseApproach -> FineApproach -> Control + // (see process_state_transition()) + if (current_state_ != Control) { + return false; + } + + // control state is done when the ball is slowed AND in mouth + // TODO(Kevin): make these into ROS planning params + double ball_slow_cutoff = 0.01; // m/s = ~10% robot radius/s + bool ball_is_slow = average_ball_vel_initialized_ && average_ball_vel_.mag() < ball_slow_cutoff; + + // ideal ball-mouth distance = 1 kRobotRadius + 1 kBallRadius + // give some leeway with ball_in_mouth_cutoff + double ball_in_mouth_cutoff = 0.01; + double dist_to_ball = (cached_robot_pos_.value() - cached_ball_pos_.value()).mag(); + bool ball_in_mouth = dist_to_ball - (kRobotRadius + kBallRadius) < ball_in_mouth_cutoff; + + return ball_is_slow && ball_in_mouth; +} + } // namespace planning diff --git a/soccer/src/soccer/planning/planner/collect_planner.hpp b/soccer/src/soccer/planning/planner/collect_planner.hpp index b36cc184ab..48ca7c7ec0 100644 --- a/soccer/src/soccer/planning/planner/collect_planner.hpp +++ b/soccer/src/soccer/planning/planner/collect_planner.hpp @@ -3,6 +3,7 @@ #include "planning/instant.hpp" #include "planning/planner/planner.hpp" #include "planning/primitives/replanner.hpp" +#include "rj_geometry/point.hpp" namespace planning { @@ -30,6 +31,7 @@ class CollectPlanner : public PlannerForCommandType { Trajectory plan(const PlanRequest& plan_request) override; void reset() override; + [[nodiscard]] bool is_done() const override; private: // Restarts the state machine if our calculations are whack @@ -73,6 +75,11 @@ class CollectPlanner : public PlannerForCommandType { rj_geometry::Point path_coarse_target_; bool path_coarse_target_initialized_ = false; + + // is_done vars + std::optional cached_start_instant_; + std::optional cached_robot_pos_; + std::optional cached_ball_pos_; }; -} // namespace planning \ No newline at end of file +} // namespace planning diff --git a/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.cpp b/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.cpp index d06f4e788d..30864900c9 100644 --- a/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.cpp +++ b/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.cpp @@ -23,8 +23,6 @@ Trajectory EscapeObstaclesPathPlanner::plan(const PlanRequest& plan_request) { // Keep moving, but slow down the current velocity. This allows us to // keep continuity when we have short disruptions in planners (i.e. // single frame delay). - // TODO(#1464): When the assignment delay is fixed, remove this horrible - // hack by using Twist::Zero() instead of start_instant.velocity * 0.8 Trajectory result{ {RobotInstant{start_instant.pose, start_instant.velocity * 0.0, start_instant.stamp}}}; result.mark_angles_valid(); @@ -91,4 +89,11 @@ Point EscapeObstaclesPathPlanner::find_non_blocked_goal(Point goal, std::optiona return goal; } +bool EscapeObstaclesPathPlanner::is_done() const { + // Since this is the lowest priority planner, PlannerForRobot automatically + // switches to a more suitable planner when needed. + // (see planner_node.cpp) + return false; +} + } // namespace planning diff --git a/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.hpp b/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.hpp index ea1dce0524..eb71a0ba49 100644 --- a/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.hpp +++ b/soccer/src/soccer/planning/planner/escape_obstacles_path_planner.hpp @@ -32,6 +32,8 @@ class EscapeObstaclesPathPlanner : public Planner { Trajectory plan(const PlanRequest& plan_request) override; + // if no other planners apply, this one does (see the order of planners in + // planner_node.cpp) [[nodiscard]] bool is_applicable( const MotionCommand& /* command */) const override { return true; @@ -48,6 +50,7 @@ class EscapeObstaclesPathPlanner : public Planner { static double step_size() { return escape::PARAM_step_size; } void reset() override { previous_target_ = std::nullopt; } + [[nodiscard]] bool is_done() const override; private: PathTargetPlanner planner_; diff --git a/soccer/src/soccer/planning/planner/intercept_planner.cpp b/soccer/src/soccer/planning/planner/intercept_planner.cpp index 6e18f876d0..3929005e00 100644 --- a/soccer/src/soccer/planning/planner/intercept_planner.cpp +++ b/soccer/src/soccer/planning/planner/intercept_planner.cpp @@ -78,4 +78,6 @@ Trajectory InterceptPlanner::plan(const PlanRequest& plan_request) { return trajectory; } +bool InterceptPlanner::is_done() const { return false; } + } // namespace planning diff --git a/soccer/src/soccer/planning/planner/intercept_planner.hpp b/soccer/src/soccer/planning/planner/intercept_planner.hpp index 4a86e6cf51..161db3d21a 100644 --- a/soccer/src/soccer/planning/planner/intercept_planner.hpp +++ b/soccer/src/soccer/planning/planner/intercept_planner.hpp @@ -18,5 +18,7 @@ class InterceptPlanner : public PlannerForCommandType { : PlannerForCommandType("InterceptPlanner"){}; Trajectory plan(const PlanRequest& request) override; + + [[nodiscard]] bool is_done() const override; }; } // namespace planning diff --git a/soccer/src/soccer/planning/planner/line_kick_planner.cpp b/soccer/src/soccer/planning/planner/line_kick_planner.cpp index e7b0bc5d50..e02a3975f4 100644 --- a/soccer/src/soccer/planning/planner/line_kick_planner.cpp +++ b/soccer/src/soccer/planning/planner/line_kick_planner.cpp @@ -13,6 +13,7 @@ using namespace rj_geometry; namespace planning { Trajectory LineKickPlanner::plan(const PlanRequest& plan_request) { + // TODO(Kevin): ros params here const float approach_speed = 0.25; const float ball_avoid_distance = 0.05; @@ -34,6 +35,20 @@ Trajectory LineKickPlanner::plan(const PlanRequest& plan_request) { const auto& rotation_constraints = plan_request.constraints.rot; const auto& ball = plan_request.world_state->ball; + // track ball velocity to know if done or not + if (!average_ball_vel_initialized_) { + average_ball_vel_ = ball.velocity; + average_ball_vel_initialized_ = true; + } else { + // Add the newest ball velocity measurement to the average velocity + // estimate, but downweight the new value heavily + // + // 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); + } + if (prev_path_.empty()) { final_approach_ = false; } @@ -75,8 +90,8 @@ Trajectory LineKickPlanner::plan(const PlanRequest& plan_request) { } #endif - // TODO(Kyle): This is laughably high - if (ball.velocity.mag() < 10.0) { + // only plan line kick if not is_done + if (!this->is_done()) { LinearMotionInstant target{ball.position, (command.target - ball.position).normalized(approach_speed)}; @@ -134,6 +149,7 @@ Trajectory LineKickPlanner::plan(const PlanRequest& plan_request) { } return Trajectory{}; + // (Kevin) pretty sure everything under this line is not used if (!prev_path_.empty() && target_kick_pos_) { auto previous_duration_remaining = prev_path_.end_time() - start_instant.stamp; @@ -252,4 +268,10 @@ Trajectory LineKickPlanner::plan(const PlanRequest& plan_request) { return path; } +bool LineKickPlanner::is_done() const { + // if ball is fast, assume we have kicked it correctly + // (either way we can't go recapture it) + return average_ball_vel_.mag() > IS_DONE_BALL_VEL; +} + } // namespace planning diff --git a/soccer/src/soccer/planning/planner/line_kick_planner.hpp b/soccer/src/soccer/planning/planner/line_kick_planner.hpp index 11850eb1d0..1f875546b8 100644 --- a/soccer/src/soccer/planning/planner/line_kick_planner.hpp +++ b/soccer/src/soccer/planning/planner/line_kick_planner.hpp @@ -30,12 +30,20 @@ class LineKickPlanner : public PlannerForCommandType target_kick_pos_ = std::nullopt; reuse_path_count_ = 0; } + [[nodiscard]] bool is_done() const override; private: Trajectory prev_path_; bool final_approach_ = false; std::optional target_kick_pos_; int reuse_path_count_ = 0; + + // ball velocity filtering vars + rj_geometry::Point average_ball_vel_; + bool average_ball_vel_initialized_ = false; + + // TODO(Kevin): ros params here + double IS_DONE_BALL_VEL = 0.5; // m/s }; } // namespace planning diff --git a/soccer/src/soccer/planning/planner/path_target_planner.cpp b/soccer/src/soccer/planning/planner/path_target_planner.cpp index 1b0ab290e6..2504fcc79b 100644 --- a/soccer/src/soccer/planning/planner/path_target_planner.cpp +++ b/soccer/src/soccer/planning/planner/path_target_planner.cpp @@ -2,10 +2,12 @@ #include +#include + #include "planning/instant.hpp" -#include "planning/trajectory.hpp" #include "planning/planner/plan_request.hpp" #include "planning/primitives/velocity_profiling.hpp" +#include "planning/trajectory.hpp" using namespace rj_geometry; @@ -30,6 +32,10 @@ Trajectory PathTargetPlanner::plan(const PlanRequest& request) { LinearMotionInstant goal_instant = command.goal; Point goal_point = goal_instant.position; + // Cache the start and goal instants for is_done() + cached_goal_instant_ = goal_instant; + cached_start_instant_ = request.start.linear_motion(); + // Debug drawing if (request.debug_drawer != nullptr) { request.debug_drawer->draw_circle(Circle(goal_point, static_cast(draw_radius)), @@ -48,6 +54,31 @@ Trajectory PathTargetPlanner::plan(const PlanRequest& request) { return trajectory; } +bool PathTargetPlanner::is_done() const { + if (!cached_start_instant_.has_value() || !cached_goal_instant_.has_value()) { + return false; + } + + // maximum difference in position and velocity that we can still + // consider close enough (in m) + // TODO(#1913): connect gameplay to planner is_done to avoid two diff threshold params + double temp_correction = 1.2; // be X% more generous than gameplay so we can see change + + // TODO(Kevin): also, should enforce the desired angle + // right now there is a convoluted chain + // PathTargetPlanner->Replanner->plan_angles which plans angles depending + // on AngleFunction (either desired face point or desired face angle). + // nowhere in the chain is there a check if PathTargetPlanner actually is + // getting to the desired angle. + // + // may be related to issue #1506? + double position_tolerance = 1e-2 * temp_correction; + double velocity_tolerance = 1e-1 * temp_correction; + return LinearMotionInstant::nearly_equals(cached_start_instant_.value(), + cached_goal_instant_.value(), position_tolerance, + velocity_tolerance); +} + AngleFunction PathTargetPlanner::get_angle_function(const PlanRequest& request) { auto angle_override = std::get(request.motion_command).angle_override; if (std::holds_alternative(angle_override)) { diff --git a/soccer/src/soccer/planning/planner/path_target_planner.hpp b/soccer/src/soccer/planning/planner/path_target_planner.hpp index 6a3d2e0170..45165208ff 100644 --- a/soccer/src/soccer/planning/planner/path_target_planner.hpp +++ b/soccer/src/soccer/planning/planner/path_target_planner.hpp @@ -1,10 +1,13 @@ #pragma once -#include #include +#include + #include "planner.hpp" +#include "planning/instant.hpp" #include "planning/primitives/replanner.hpp" #include "planning/primitives/velocity_profiling.hpp" +#include "rj_geometry/pose.hpp" namespace planning { @@ -21,6 +24,8 @@ class PathTargetPlanner : public PlannerForCommandType { Trajectory plan(const PlanRequest& request) override; void reset() override { previous_ = Trajectory(); } + [[nodiscard]] bool is_done() const override; + double draw_radius = kRobotRadius; QColor draw_color = Qt::black; @@ -29,6 +34,10 @@ class PathTargetPlanner : public PlannerForCommandType { const PlanRequest& request); Trajectory previous_; + + // vars to tell if is_done + std::optional cached_start_instant_; + std::optional cached_goal_instant_; }; } // namespace planning diff --git a/soccer/src/soccer/planning/planner/pivot_path_planner.cpp b/soccer/src/soccer/planning/planner/pivot_path_planner.cpp index 5500b47239..e07251bf7d 100644 --- a/soccer/src/soccer/planning/planner/pivot_path_planner.cpp +++ b/soccer/src/soccer/planning/planner/pivot_path_planner.cpp @@ -67,6 +67,8 @@ Trajectory PivotPathPlanner::plan(const PlanRequest& request) { double target_angle = pivot_point.angle_to(final_position); double angle_change = fix_angle_radians(target_angle - start_angle); + cached_angle_change_ = angle_change; + constexpr double kMaxInterpolationRadians = 10 * M_PI / 180; const int interpolations = std::ceil(std::abs(angle_change) / kMaxInterpolationRadians); @@ -98,4 +100,12 @@ Trajectory PivotPathPlanner::plan(const PlanRequest& request) { return path; } -} // namespace planning \ No newline at end of file +bool PivotPathPlanner::is_done() const { + if (!cached_angle_change_.has_value()) { + return false; + } + + return cached_angle_change_.value() < IS_DONE_ANGLE_CHANGE_THRESH; +} + +} // namespace planning diff --git a/soccer/src/soccer/planning/planner/pivot_path_planner.hpp b/soccer/src/soccer/planning/planner/pivot_path_planner.hpp index c6266ab319..68ef50c623 100644 --- a/soccer/src/soccer/planning/planner/pivot_path_planner.hpp +++ b/soccer/src/soccer/planning/planner/pivot_path_planner.hpp @@ -21,6 +21,7 @@ class PivotPathPlanner : public PlannerForCommandType { cached_pivot_target_ = std::nullopt; cached_pivot_point_ = std::nullopt; } + [[nodiscard]] bool is_done() const override; private: Trajectory previous_; @@ -28,5 +29,12 @@ class PivotPathPlanner : public PlannerForCommandType { // Cache the pivot point and target so we don't just push the ball across the field. std::optional cached_pivot_point_; std::optional cached_pivot_target_; + + // cache the most recent angle change so we know when we're done + std::optional cached_angle_change_; + + // TODO(Kevin): ros param this + // in gameplay it is 0.05, this is just to see the change + double IS_DONE_ANGLE_CHANGE_THRESH = 0.1; }; -} // namespace planning \ No newline at end of file +} // namespace planning diff --git a/soccer/src/soccer/planning/planner/planner.hpp b/soccer/src/soccer/planning/planner/planner.hpp index 69dcc09bca..6dfe0b18cf 100644 --- a/soccer/src/soccer/planning/planner/planner.hpp +++ b/soccer/src/soccer/planning/planner/planner.hpp @@ -42,6 +42,11 @@ class Planner { */ virtual void reset() {} + /* + * @return true if planner is done, false otherwise. + */ + [[nodiscard]] virtual bool is_done() const = 0; + /** * Get a user-readable name for this planner. */ diff --git a/soccer/src/soccer/planning/planner/settle_planner.cpp b/soccer/src/soccer/planning/planner/settle_planner.cpp index 71d253385a..0a19bda7e8 100644 --- a/soccer/src/soccer/planning/planner/settle_planner.cpp +++ b/soccer/src/soccer/planning/planner/settle_planner.cpp @@ -536,4 +536,18 @@ void SettlePlanner::reset() { previous_ = Trajectory{}; } +bool SettlePlanner::is_done() const { + // FSM: Intercept -> Dampen + // (see process_state_transition()) + if (current_state_ != SettlePlannerStates::Dampen) { + return false; + } + + // Dampen is done when the ball is slow-ish, let collect handle actually + // taking possession + // TODO(Kevin): consider making settle + collect one planner + double SETTLE_BALL_SPEED_THRESHOLD = 0.75; + return average_ball_vel_.mag() < SETTLE_BALL_SPEED_THRESHOLD; +} + } // namespace planning diff --git a/soccer/src/soccer/planning/planner/settle_planner.hpp b/soccer/src/soccer/planning/planner/settle_planner.hpp index 2378d353ee..b6591b9fa1 100644 --- a/soccer/src/soccer/planning/planner/settle_planner.hpp +++ b/soccer/src/soccer/planning/planner/settle_planner.hpp @@ -29,6 +29,7 @@ class SettlePlanner : public PlannerForCommandType { Trajectory plan(const PlanRequest& plan_request) override; void reset() override; + [[nodiscard]] bool is_done() const override; static void create_configuration(Configuration* cfg); diff --git a/soccer/src/soccer/planning/planner_node.cpp b/soccer/src/soccer/planning/planner_node.cpp index 6fc5988f27..e8e23f5c6b 100644 --- a/soccer/src/soccer/planning/planner_node.cpp +++ b/soccer/src/soccer/planning/planner_node.cpp @@ -22,7 +22,7 @@ PlannerNode::PlannerNode() robots_planners_.reserve(kNumShells); for (int i = 0; i < kNumShells; i++) { auto planner = - std::make_unique(i, this, &robot_trajectories_, &shared_state_); + std::make_shared(i, this, &robot_trajectories_, &shared_state_); robots_planners_.emplace_back(std::move(planner)); } } @@ -37,14 +37,14 @@ PlannerForRobot::PlannerForRobot(int robot_id, rclcpp::Node* node, debug_draw_{ node->create_publisher(viz::topics::kDebugDrawPub, 10), fmt::format("planning_{}", robot_id)} { - planners_.push_back(std::make_unique()); - planners_.push_back(std::make_unique()); - planners_.push_back(std::make_unique()); - planners_.push_back(std::make_unique()); - planners_.push_back(std::make_unique()); + planners_.push_back(std::make_shared()); + planners_.push_back(std::make_shared()); + planners_.push_back(std::make_shared()); + planners_.push_back(std::make_shared()); + planners_.push_back(std::make_shared()); // The empty planner should always be last. - planners_.push_back(std::make_unique()); + planners_.push_back(std::make_shared()); // Set up ROS trajectory_pub_ = node_->create_publisher( @@ -88,6 +88,9 @@ PlanRequest PlannerForRobot::make_request(const RobotIntent& intent) { std::array planned_trajectories = {}; for (int i = 0; i < kNumShells; i++) { + // TODO(Kevin): check that priority works (seems like + // robot_trajectories_ is passed on init, when no planning has occured + // yet) const auto& [trajectory, priority] = robot_trajectories_hold.at(i); if (i != robot_id_ && priority >= intent.priority) { planned_trajectories.at(i) = trajectory.get(); @@ -122,12 +125,14 @@ Trajectory PlannerForRobot::plan_for_robot(const planning::PlanRequest& request) // If this planner could possibly plan for this command, try to make // a plan. if (trajectory.empty() && planner->is_applicable(request.motion_command)) { + current_planner_ = planner; trajectory = planner->plan(request); } // If it fails, or if the planner was not used, the trajectory will // still be empty. Reset the planner. if (trajectory.empty()) { + current_planner_ = nullptr; planner->reset(); } else { if (!trajectory.angles_valid()) { @@ -158,11 +163,26 @@ Trajectory PlannerForRobot::plan_for_robot(const planning::PlanRequest& request) debug_draw_.publish(); + // TODO(Kevin): delete this debug print + if (this->is_done()) { + SPDLOG_ERROR("robot {}'s {} is_done", robot_id_, current_planner_->name()); + } + return trajectory; } + bool PlannerForRobot::robot_alive() const { return shared_state_->world_state()->our_robots.at(robot_id_).visible && RJ::now() < shared_state_->world_state()->last_updated_time + RJ::Seconds(PARAM_timeout); } +bool PlannerForRobot::is_done() const { + // no segfaults + if (current_planner_ == nullptr) { + return false; + } + + return current_planner_->is_done(); +} + } // namespace planning diff --git a/soccer/src/soccer/planning/planner_node.hpp b/soccer/src/soccer/planning/planner_node.hpp index edf1811a53..54fe6845d0 100644 --- a/soccer/src/soccer/planning/planner_node.hpp +++ b/soccer/src/soccer/planning/planner_node.hpp @@ -126,6 +126,10 @@ class SharedStateInfo { WorldState last_world_state_; }; +/** + * Interface for one robot's planning, which for us is a RobotIntent to Trajectory + * translation. Planner node makes N PlannerForRobots and handles them all. + */ class PlannerForRobot { public: PlannerForRobot(int robot_id, rclcpp::Node* node, TrajectoryCollection* robot_trajectories, @@ -139,13 +143,45 @@ class PlannerForRobot { ~PlannerForRobot() = default; private: + /** + * @brief Create a PlanRequest based on the given RobotIntent. + * + * @details This is how gameplay's RobotIntents end up in the right planner (e.g. + * how a Pivot skill goes to PivotPath planner). + * + * @param intent RobotIntent msg + * + * @return PlanRequest based on input RobotIntent + */ PlanRequest make_request(const RobotIntent& intent); + + /* + * @brief Get a Trajectory based on the PlanRequest by ticking through all + * available planners. + * + * @details (Each planner implements an "is_applicable(PlanRequest.motion_command)"). + * + * @param request PlanRequest that needs a motion plan made + * + * @return Trajectory (timestamped series of poses & twists) that satisfies + * the PlanRequest as well as possible + */ Trajectory plan_for_robot(const planning::PlanRequest& request); + /* + * @brief Check that robot is visible in world_state and that world_state has been + * updated recently. + */ [[nodiscard]] bool robot_alive() const; + /* + * @return true if current planner is done, false otherwise. + */ + [[nodiscard]] bool is_done() const; + rclcpp::Node* node_; - std::vector> planners_; + std::vector> planners_; + std::shared_ptr current_planner_; int robot_id_; TrajectoryCollection* robot_trajectories_; @@ -160,12 +196,15 @@ class PlannerForRobot { rj_drawing::RosDebugDrawer debug_draw_; }; +/** + * ROS node that spawns many PlannerForRobots and helps coordinate them. + */ class PlannerNode : public rclcpp::Node { public: PlannerNode(); private: - std::vector> robots_planners_; + std::vector> robots_planners_; TrajectoryCollection robot_trajectories_; SharedStateInfo shared_state_; ::params::LocalROS2ParamProvider param_provider_; diff --git a/soccer/src/soccer/planning/planning_params.cpp b/soccer/src/soccer/planning/planning_params.cpp index 111a5863ac..e367d3cb6d 100644 --- a/soccer/src/soccer/planning/planning_params.cpp +++ b/soccer/src/soccer/planning/planning_params.cpp @@ -62,7 +62,7 @@ DEFINE_NS_FLOAT64( // // High number indicates that it will always try to choose a point nearest // to the current robot position -DEFINE_NS_FLOAT64(kPlanningParamModule, collect, ball_speed_approach_direction_cutoff, 0.1, +DEFINE_NS_FLOAT64(kPlanningParamModule, collect, ball_speed_approach_direction_cutoff, 1.0, "Controls at which ball speed we should try to go directly to the ball " "or to move behind it and in the same direction as it (m/s)"); // How much to scale the accelerations by as a percent of the normal @@ -71,12 +71,12 @@ DEFINE_NS_FLOAT64(kPlanningParamModule, collect, ball_speed_approach_direction_c // Approach acceleration controls all the movement from the start location // to right before touching the ball DEFINE_NS_FLOAT64( - kPlanningParamModule, collect, approach_accel_scale, 0.7, + kPlanningParamModule, collect, approach_accel_scale, 1.0, "How much to scale the accelerations by as a percent of the normal acceleration (unitless)"); // Control acceleration controls the touch to stop // Lower this if we decelerate too quickly for the dribbler to keep a back // spin on -DEFINE_NS_FLOAT64(kPlanningParamModule, collect, control_accel_scale, 0.2, +DEFINE_NS_FLOAT64(kPlanningParamModule, collect, control_accel_scale, 1.0, "Control acceleration controls the touch to stop (unitless)"); // How far away from the ball to target for the approach // This should be tuned so that the end of approach places the dribbler @@ -90,7 +90,7 @@ DEFINE_NS_FLOAT64(kPlanningParamModule, collect, approach_dist_target, 0.01, // we still are able to touch the ball and control it If we are slamming // into the ball decrease this number If we aren't even touching it to the // dribbler, increase this number (And check the approach_dist_target) -DEFINE_NS_FLOAT64(kPlanningParamModule, collect, touch_delta_speed, 0.15, +DEFINE_NS_FLOAT64(kPlanningParamModule, collect, touch_delta_speed, 0.01, "At what speed should we be when we touch the ball (m/s)"); DEFINE_NS_FLOAT64(kPlanningParamModule, collect, velocity_control_scale, 1.0, "The amount (unitless)"); @@ -111,7 +111,7 @@ DEFINE_NS_FLOAT64( // If we are trying to transition with a large delta velocity between the robot and the ball // decrease this number. DEFINE_NS_FLOAT64( - kPlanningParamModule, collect, vel_cutoff_to_control, 0.3, + kPlanningParamModule, collect, vel_cutoff_to_control, 0.02, "How close to the target velocity do we have to be before transferring to the control " "state (m/s)"); // How much extra room should we stay at the delta speed before slowing down. @@ -121,7 +121,7 @@ DEFINE_NS_FLOAT64( // through the entire sequence. Increasing this number makes the robot state // at delta velocity longer. DEFINE_NS_FLOAT64( - kPlanningParamModule, collect, stop_dist_scale, 1, + kPlanningParamModule, collect, stop_dist_scale, 0.8, "Portion of maximum stopping distance for which we stay at the delta speed (unitless)"); // Gain on the averaging function to smooth the target point to intercept // This is due to the high flucations in the ball velocity frame to frame @@ -130,7 +130,7 @@ DEFINE_NS_FLOAT64( // it responds to changes The higher the number, the more noise affects the // system, but the faster it responds to changes DEFINE_NS_FLOAT64( - kPlanningParamModule, collect, target_point_lowpass_gain, 0.8, + kPlanningParamModule, collect, target_point_lowpass_gain, 0.6, "Gain on the averaging function to smooth the target point to intercept (unitless)"); // How much of the ball seed to contact the ball with diff --git a/soccer/src/soccer/planning/primitives/create_path.cpp b/soccer/src/soccer/planning/primitives/create_path.cpp index 78ac11ffee..11feff152d 100644 --- a/soccer/src/soccer/planning/primitives/create_path.cpp +++ b/soccer/src/soccer/planning/primitives/create_path.cpp @@ -30,9 +30,11 @@ Trajectory rrt(const LinearMotionInstant& start, const LinearMotionInstant& goal const ShapeSet& static_obstacles, const std::vector& dynamic_obstacles, const std::vector& bias_waypoints) { + // if already on goal, no need to move if (start.position.dist_to(goal.position) < 1e-6) { return Trajectory{{RobotInstant{Pose(start.position, 0), Twist(), start_time}}}; } + // maybe we don't need an RRT Trajectory straight_trajectory = CreatePath::simple(start, goal, motion_constraints, start_time);