diff --git a/docker/runner/docker-compose.yml b/docker/runner/docker-compose.yml index 6e1b1d1bc..c5e4cc72c 100644 --- a/docker/runner/docker-compose.yml +++ b/docker/runner/docker-compose.yml @@ -18,7 +18,7 @@ services: - LD_LIBRARY_PATH=/home/roboteamtwente/lib/ volumes: - ../../build/release/:/home/roboteamtwente/ - profiles: ["simulator","diff","game"] + profiles: ["simulator","diff","game", "robocup"] roboteam_secondary_ai: image: roboteamtwente/roboteam:development @@ -61,7 +61,7 @@ services: container_name: RTT_roboteam_observer_sim restart: always working_dir: "/home/roboteamtwente/" - command: sh -c "./bin/roboteam_observer --vision-ip 224.5.23.2 --referee-ip 224.5.23.1 --vision-port 10020 --referee-port 10003" + command: sh -c "./bin/roboteam_observer --vision-ip 224.5.23.2 --referee-ip 224.5.23.1 --vision-port 10020 --referee-port 10003 --log" network_mode: "host" # Workaround to connect from interface on host to AI websocket, please fix expose: - 1-65535:1-65535 # For zeromq ports @@ -79,7 +79,7 @@ services: container_name: RTT_roboteam_observer_game restart: always working_dir: "/home/roboteamtwente/" - command: sh -c "./bin/roboteam_observer --vision-ip 224.5.23.2 --referee-ip 224.5.23.1 --vision-port 10006 --referee-port 10003" + command: sh -c "./bin/roboteam_observer --vision-ip 224.5.23.2 --referee-ip 224.5.23.1 --vision-port 10006 --referee-port 10003 --log" network_mode: "host" # Workaround to connect from interface on host to AI websocket, please fix expose: - 1-65535:1-65535 # For zeromq ports @@ -90,7 +90,7 @@ services: - LD_LIBRARY_PATH=/home/roboteamtwente/lib/ volumes: - ../../build/release/:/home/roboteamtwente/ - profiles: ["game","autoref"] + profiles: ["game","autoref", "robocup"] roboteam_robothub_sim: image: roboteamtwente/roboteam:development @@ -135,7 +135,7 @@ services: privileged: true devices: - /dev/rtt-basestation:/dev/ttyACM1 - profiles: ["game"] + profiles: ["game", "robocup"] roboteam_interface: image: roboteamtwente/roboteam:development @@ -147,7 +147,7 @@ services: - 8080:8080 volumes: - ../../roboteam_interface/:/home/roboteamtwente/ - profiles: ["simulator","diff","game"] + profiles: ["simulator","diff","game", "robocup"] roboteam_autoref: image: gradle:8.4.0-jdk17 diff --git a/roboteam_ai/include/roboteam_ai/utilities/Constants.h b/roboteam_ai/include/roboteam_ai/utilities/Constants.h index 528c23a11..a699701be 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/Constants.h +++ b/roboteam_ai/include/roboteam_ai/utilities/Constants.h @@ -44,11 +44,9 @@ constexpr double MAX_VEL_WHEN_HAS_BALL = 3.0; /**< Maximum allowed velocity that constexpr double MAX_ANGULAR_VELOCITY = 6.0; /**< Maximum allowed angular velocity that can be send to the robot */ constexpr double MIN_YAW = -M_PI; /**< Minimum yaw the robot can have */ constexpr double MAX_YAW = M_PI; /**< Maximum yaw the robot can have */ -constexpr double MAX_ACC = 3.5; /**< Maximum acceleration of the robot */ -constexpr double MAX_VEL = 4.0; /**< Maximum allowed velocity of the robot */ -constexpr double MAX_JERK_OVERSHOOT = 100; /**< Jerk limit for overshoot */ -// TODO ROBOCUP 2024: FIX THIS MAGIC -constexpr double MAX_JERK_DEFAULT = 6; /**< Default jerk limit */ +constexpr double MAX_ACC = 2.0; /**< Maximum acceleration of the robot */ +constexpr double MAX_VEL = 2.0; /**< Maximum allowed velocity of the robot */ +constexpr double MAX_JERK_DEFAULT = 6; /**< Default jerk limit */ /// GoToPos Constants // Distance margin for 'goToPos'. If the robot is within this margin, goToPos is successful @@ -57,7 +55,7 @@ constexpr double GO_TO_POS_ERROR_MARGIN = 0.02; /**< Distance error for a robot constexpr double GO_TO_POS_ANGLE_ERROR_MARGIN = 0.01; /**< Angle error for a robot to be considered to have reached a position */ // Maximum inaccuracy during ballplacement constexpr double BALL_PLACEMENT_MARGIN = 0.15 - BALL_RADIUS - 0.01; /**< Distance error for the ball to be considered to have reached the ball placement position*/ -constexpr double BALL_PLACER_MARGIN = BALL_PLACEMENT_MARGIN - 0.05; /**< Distance before the ball placer moves away from hte ball*/ +constexpr double BALL_PLACER_MARGIN = BALL_PLACEMENT_MARGIN - 0.07; /**< Distance before the ball placer moves away from hte ball*/ constexpr double ENEMY_ALREADY_ASSIGNED_MULTIPLIER = 0.9; /**< Multiplication factor for the distance to goal used by the dealer when the enemy is already assigned */ /// Invariant constants @@ -80,7 +78,7 @@ constexpr double AVOID_BALL_DISTANCE_BEFORE_FREE_KICK = /// Friction constants constexpr static float SIMULATION_FRICTION = 0.71; /**< The expected movement friction of the ball during simulation */ -constexpr static float REAL_FRICTION = 0.44; /**< The expected movement friction of the ball on the field */ +constexpr static float REAL_FRICTION = 0.526; /**< The expected movement friction of the ball on the field */ static inline double HAS_BALL_DISTANCE() { return (GameSettings::getRobotHubMode() == net::RobotHubMode::BASESTATION) ? 0.11 : 0.12; } static inline double SEND_TIME_IN_FUTURE() { diff --git a/roboteam_ai/include/roboteam_ai/utilities/RuleSet.h b/roboteam_ai/include/roboteam_ai/utilities/RuleSet.h index 8cc2b2bd2..6d6bd3bbc 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/RuleSet.h +++ b/roboteam_ai/include/roboteam_ai/utilities/RuleSet.h @@ -49,9 +49,9 @@ struct RuleSet { } } - static constexpr RuleSet RULESET_DEFAULT() { return {RuleSetName::DEFAULT, 4.0}; } + static constexpr RuleSet RULESET_DEFAULT() { return {RuleSetName::DEFAULT, 2.0}; } static constexpr RuleSet RULESET_HALT() { return {RuleSetName::HALT, 0.0}; } - static constexpr RuleSet RULESET_STOP() { return {RuleSetName::STOP, 1.3}; } + static constexpr RuleSet RULESET_STOP() { return {RuleSetName::STOP, 1.0}; } static constexpr std::array ruleSets() { return { diff --git a/roboteam_ai/src/control/ControlUtils.cpp b/roboteam_ai/src/control/ControlUtils.cpp index 05d9c9598..7c26bfdda 100644 --- a/roboteam_ai/src/control/ControlUtils.cpp +++ b/roboteam_ai/src/control/ControlUtils.cpp @@ -23,9 +23,9 @@ double ControlUtils::determineKickForce(const double distance, stp::ShotPower sh double kickForce; if (shotPower == stp::ShotPower::PASS) { - kickForce = 0.8; + kickForce = 1.8; } else if (shotPower == stp::ShotPower::TARGET) { - kickForce = 0.5; + kickForce = 1.2; } else { RTT_WARNING("No shotPower set! Setting kickForce to 0") kickForce = 0; diff --git a/roboteam_ai/src/control/positionControl/CollisionCalculations.cpp b/roboteam_ai/src/control/positionControl/CollisionCalculations.cpp index 84236b9d8..d7fbe7d4b 100644 --- a/roboteam_ai/src/control/positionControl/CollisionCalculations.cpp +++ b/roboteam_ai/src/control/positionControl/CollisionCalculations.cpp @@ -9,8 +9,8 @@ namespace rtt::ai::control { double CollisionCalculations::getFirstCollisionTimeMotionlessObject(const Trajectory2D &Trajectory, stp::AvoidObjects avoidObjects, const Field &field) { - auto pathPoints = Trajectory.getPathApproach(0.1); - auto maxCheckPoints = std::min(pathPoints.size(), static_cast(7)); + auto pathPoints = Trajectory.getPathApproach(0.05); + auto maxCheckPoints = std::min(pathPoints.size(), static_cast(14)); auto [theirDefenseAreaMargin, ourDefenseAreaMargin] = FieldComputations::getDefenseAreaMargin(); const auto &ourDefenseArea = FieldComputations::getDefenseArea(field, true, ourDefenseAreaMargin, 1); @@ -36,17 +36,17 @@ double CollisionCalculations::getFirstCollisionTimeMotionlessObject(const Trajec } if (avoidObjects.shouldAvoidOurDefenseArea) { if (ourDefenseArea.contains(pathPoints[checkPoint]) || ourDefenseArea.contains(pathPoints[checkPoint - 1]) || ourDefenseArea.doesIntersect(pathLine)) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } if (avoidObjects.shouldAvoidTheirDefenseArea && theirDefenseAreaMargin > constants::ROBOT_RADIUS + constants::GO_TO_POS_ERROR_MARGIN) { if (theirDefenseArea.contains(pathPoints[checkPoint]) || theirDefenseArea.contains(pathPoints[checkPoint - 1]) || theirDefenseArea.doesIntersect(pathLine)) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } if (avoidObjects.shouldAvoidOutOfField) { if (!field.playArea.contains(pathPoints[checkPoint], constants::OUT_OF_FIELD_MARGIN)) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } } @@ -60,7 +60,7 @@ bool CollisionCalculations::isCollidingWithMotionlessObject(const Trajectory2D & double CollisionCalculations::getFirstCollisionTimeMovingObject(const Trajectory2D &Trajectory, stp::AvoidObjects avoidObjects, int &robotId, const world::World *world, const std::unordered_map> &computedPaths) { - auto pathPoints = Trajectory.getPathApproach(0.1); + auto pathPoints = Trajectory.getPathApproach(0.05); auto maxCheckPoints = std::min(pathPoints.size(), static_cast(7)); const std::vector &theirRobots = world->getWorld()->getThem(); @@ -70,21 +70,22 @@ double CollisionCalculations::getFirstCollisionTimeMovingObject(const Trajectory for (int checkPoint = 1; checkPoint < static_cast(maxCheckPoints); checkPoint += 1) { auto pathLine = LineSegment(pathPoints[checkPoint - 1], pathPoints[checkPoint]); - double velocityOurRobot = Trajectory.getVelocity(checkPoint * 0.1).length(); - auto positionOurRobot = Trajectory.getPosition(checkPoint * 0.1); - double additionalMargin = std::pow(std::min(maxVel, velocityOurRobot) / maxVel, 2) * 0.2; - if (velocityOurRobot > 0.4 && avoidObjects.shouldAvoidOurRobots) { + double velocityOurRobot = Trajectory.getVelocity(checkPoint * 0.05).length(); + auto positionOurRobot = Trajectory.getPosition(checkPoint * 0.05); + double additionalMargin = std::pow(std::min(3.5, velocityOurRobot) / 3.5, 2) * 0.2; + if (velocityOurRobot > 0.7 && avoidObjects.shouldAvoidOurRobots) { for (const auto &ourOtherRobot : ourRobots) { const int &ourOtherRobotId = ourOtherRobot->getId(); if (ourOtherRobotId == robotId) { continue; } + const auto computedPathsIt = computedPaths.find(ourOtherRobotId); // If the path of the other robot is not computed, we assume it is not moving if (computedPathsIt == computedPaths.end()) { const Vector2 &ourOtherRobotPos = ourOtherRobot->getPos(); if ((ourOtherRobotPos - positionOurRobot).length() < 2 * constants::ROBOT_RADIUS + additionalMargin) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } else { LineSegment pathLineOtherRobot; @@ -94,36 +95,52 @@ double CollisionCalculations::getFirstCollisionTimeMovingObject(const Trajectory pathLineOtherRobot = LineSegment(computedPathsIt->second.back(), computedPathsIt->second.back()); } if (pathLineOtherRobot.closestDistanceToLineSegment(pathLine) < 2 * constants::ROBOT_RADIUS + additionalMargin) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } } + } else if (avoidObjects.shouldAvoidOurRobots) { + for (const auto &ourOtherRobot : ourRobots) { + const int &ourOtherRobotId = ourOtherRobot->getId(); + if (ourOtherRobotId == robotId) { + continue; + } + const Vector2 &ourOtherRobotPos = ourOtherRobot->getPos(); + if ((ourOtherRobotPos - positionOurRobot).length() < 1.4 * constants::ROBOT_RADIUS) { + return checkPoint * 0.05; + } + } } if (velocityOurRobot > 0.7 && avoidObjects.shouldAvoidTheirRobots) { if (std::any_of(theirRobots.begin(), theirRobots.end(), [&](const auto &theirRobot) { - return LineSegment(theirRobot->getPos() + theirRobot->getVel() * 0.1 * (checkPoint - 1), theirRobot->getPos() + theirRobot->getVel() * 0.1 * checkPoint) + return LineSegment(theirRobot->getPos() + theirRobot->getVel() * 0.05 * (checkPoint - 1), theirRobot->getPos() + theirRobot->getVel() * 0.05 * checkPoint) .closestDistanceToLineSegment(pathLine) < 2 * constants::ROBOT_RADIUS + additionalMargin; })) { - return checkPoint * 0.1; + return checkPoint * 0.05; + } + } else if (avoidObjects.shouldAvoidTheirRobots) { + if (std::any_of(theirRobots.begin(), theirRobots.end(), + [&](const auto &theirRobot) { return (theirRobot->getPos() - positionOurRobot).length() < 1.8 * constants::CENTER_TO_FRONT; })) { + return checkPoint * 0.05; } } if (avoidObjects.shouldAvoidBall) { - auto ballPosition = FieldComputations::getBallPositionAtTime(*world->getWorld()->getBall()->get(), checkPoint * 0.1); + auto ballPosition = FieldComputations::getBallPositionAtTime(*world->getWorld()->getBall()->get(), checkPoint * 0.05); if ((ballPosition - positionOurRobot).length() < constants::AVOID_BALL_DISTANCE + additionalMargin) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } if (GameStateManager::getCurrentGameState().getCommandId() == RefCommand::BALL_PLACEMENT_THEM || GameStateManager::getCurrentGameState().getCommandId() == RefCommand::PREPARE_FORCED_START) { auto ballPlacementPosition = GameStateManager::getRefereeDesignatedPosition(); bool isBallPlacementCollision = true; - for (int i = checkPoint; i < checkPoint + 10; i++) { - auto ballPosition = FieldComputations::getBallPositionAtTime(*world->getWorld()->getBall()->get(), checkPoint * 0.1); + for (int i = checkPoint; i < checkPoint + 20; i++) { + auto ballPosition = FieldComputations::getBallPositionAtTime(*world->getWorld()->getBall()->get(), checkPoint * 0.05); if (i >= static_cast(pathPoints.size())) { isBallPlacementCollision = false; break; } - auto positionOurRobot = Trajectory.getPosition(i * 0.1); + auto positionOurRobot = Trajectory.getPosition(i * 0.05); auto ballPlacementLine = LineSegment(ballPlacementPosition, ballPosition); if (ballPlacementLine.distanceToLine(positionOurRobot) > constants::AVOID_BALL_DISTANCE + additionalMargin) { isBallPlacementCollision = false; @@ -131,7 +148,7 @@ double CollisionCalculations::getFirstCollisionTimeMovingObject(const Trajectory } } if (isBallPlacementCollision) { - return checkPoint * 0.1; + return checkPoint * 0.05; } } } diff --git a/roboteam_ai/src/stp/computations/InterceptionComputations.cpp b/roboteam_ai/src/stp/computations/InterceptionComputations.cpp index 4120e7c74..082b7bd81 100644 --- a/roboteam_ai/src/stp/computations/InterceptionComputations.cpp +++ b/roboteam_ai/src/stp/computations/InterceptionComputations.cpp @@ -65,11 +65,17 @@ InterceptionInfo InterceptionComputations::calculateInterceptionInfo(const std:: if (interceptRobot && (*interceptRobot - pastBallPosition).length() < (futureBallPosition - pastBallPosition).length()) { auto minDistance = (*interceptRobot - pastBallPosition).length(); auto robotCloseToBallPos = *interceptRobot; - if ((world->getWorld()->getRobotClosestToBall(world::us)->get()->getPos() - pastBallPosition).length() < minDistance) { + if (world->getWorld()->getRobotClosestToBall(world::us) && + (world->getWorld()->getRobotClosestToBall(world::us)->get()->getPos() - pastBallPosition).length() < minDistance) { interceptionInfo.interceptLocation = LineSegment(futureBallPosition, pastBallPosition).project(world->getWorld()->getRobotClosestToBall(world::us)->get()->getPos()); } else { - interceptionInfo.interceptLocation = robotCloseToBallPos; + if (world->getWorld()->getRobotClosestToBall(world::them) && world->getWorld()->getRobotClosestToBall(world::them)->get()->hasBall()) { + interceptionInfo.interceptLocation = robotCloseToBallPos; + } else { + interceptionInfo.interceptLocation = + robotCloseToBallPos + (ballPosition - robotCloseToBallPos).stretchToLength(std::min(0.2, (ballPosition - robotCloseToBallPos).length())); + } } double minTimeToTarget = std::numeric_limits::max(); for (const auto &robot : ourRobots) { @@ -105,28 +111,21 @@ InterceptionInfo InterceptionComputations::calculateInterceptionInfo(const std:: } double minTimeToTarget = std::numeric_limits::max(); + std::vector velocities = {targetVelocity, Vector2(0, 0)}; for (const auto &robot : ourRobots) { - Vector2 usedTargetVelocity; - auto robotToBall = (ballPosition - robot->getPos()); - auto angle = Angle(robotToBall).shortestAngleDiff(Angle(targetVelocity)); - // TODO ROBOCUP 2024: TWEAK THIS NOT MAGIC NUMBER - auto circle = Circle(ballPosition - targetVelocity.stretchToLength(0.5), 0.5); - if (std::abs(angle) < M_PI / 4 || circle.contains(robot->getPos())) { - usedTargetVelocity = targetVelocity; - } else { - usedTargetVelocity = Vector2(0, 0); - } - auto trajectory = Trajectory2D(robot->getPos(), robot->getVel(), targetPosition, usedTargetVelocity, maxRobotVelocity, ai::constants::MAX_ACC, - ai::constants::MAX_JERK_OVERSHOOT, robot->getId()); - if (trajectory.getTotalTime() < minTimeToTarget) { - minTimeToTarget = trajectory.getTotalTime(); - interceptionInfo.interceptLocation = targetPosition; - interceptionInfo.interceptVelocity = usedTargetVelocity; - interceptionInfo.interceptId = robot->getId(); - interceptionInfo.timeToIntercept = minTimeToTarget; - auto theirClosestToBall = world->getWorld()->getRobotClosestToBall(world::them); - if (!theirClosestToBall || (robot->getPos() - targetPosition).length() < (theirClosestToBall->get()->getPos() - targetPosition).length()) { - interceptionInfo.isInterceptable = true; + for (const auto &velocity : velocities) { + auto trajectory = Trajectory2D(robot->getPos(), robot->getVel(), targetPosition, velocity, maxRobotVelocity, ai::constants::MAX_ACC, + ai::constants::MAX_JERK_DEFAULT, robot->getId()); + if (trajectory.getTotalTime() < minTimeToTarget) { + minTimeToTarget = trajectory.getTotalTime(); + interceptionInfo.interceptLocation = targetPosition; + interceptionInfo.interceptVelocity = velocity; + interceptionInfo.interceptId = robot->getId(); + interceptionInfo.timeToIntercept = minTimeToTarget; + auto theirClosestToBall = world->getWorld()->getRobotClosestToBall(world::them); + if (!theirClosestToBall || (robot->getPos() - targetPosition).length() < (theirClosestToBall->get()->getPos() - targetPosition).length()) { + interceptionInfo.isInterceptable = true; + } } } } @@ -134,12 +133,12 @@ InterceptionInfo InterceptionComputations::calculateInterceptionInfo(const std:: // If the ball is not moving, we use the current ball position if (ballVelocity.length() <= constants::BALL_STILL_VEL) { - calculateIntercept(ballPosition, Vector2(0, 0)); + calculateIntercept(ballPosition, ballVelocity); interceptionInfo.interceptVelocity = Vector2(0, 0); return interceptionInfo; } - for (double loopTime = 0.1; loopTime < 1; loopTime += 0.1) { + for (double loopTime = 0.05; loopTime < 1; loopTime += 0.05) { futureBallPosition = FieldComputations::getBallPositionAtTime(*(world->getWorld()->getBall()->get()), loopTime); pastBallPosition = FieldComputations::getBallPositionAtTime(*(world->getWorld()->getBall()->get()), loopTime - 0.1); @@ -175,8 +174,8 @@ InterceptionInfo InterceptionComputations::calculateInterceptionInfo(const std:: } return interceptionInfo; } - // TODO ROBOCUP 2024: PLEASE FIX :{} - auto ballVelFuture = (futureBallPosition - pastBallPosition) / 0.1; + // TODO ROBOCUP 2024: CHANGE BACK IF NOT QUICK ENOUGH, WE HAD 0.1S BEFORE + auto ballVelFuture = (futureBallPosition - pastBallPosition) / 0.05; calculateIntercept(futureBallPosition, ballVelFuture); // If any robot can intercept the ball in time, return that info if (loopTime >= interceptionInfo.timeToIntercept) { diff --git a/roboteam_ai/src/stp/computations/PassComputations.cpp b/roboteam_ai/src/stp/computations/PassComputations.cpp index c8bce72cc..534f5cd07 100644 --- a/roboteam_ai/src/stp/computations/PassComputations.cpp +++ b/roboteam_ai/src/stp/computations/PassComputations.cpp @@ -125,8 +125,7 @@ Grid PassComputations::getPassGrid(const Field& field) { bool PassComputations::pointIsValidReceiverLocation(Vector2 point, const std::vector& possibleReceiverLocations, const std::vector& possibleReceiverVelocities, const std::vector& possibleReceiverIds, Vector2 passLocation, Vector2 passerLocation, Vector2 passerVelocity, int passerId, const Field& field, const world::World* world) { - // TODO ROBOCUP 2024: CHECK THIS - constexpr double MINIMUM_PASS_DISTANCE = 4.0; // This can be dribbled instead of passed + constexpr double MINIMUM_PASS_DISTANCE = 3.0; // This can be dribbled instead of passed if (point.dist(passLocation) < MINIMUM_PASS_DISTANCE) return false; constexpr double MINIMUM_LINE_OF_SIGHT = 10.0; // The minimum LoS to be a valid pass, otherwise, the pass will go into an enemy robot if (PositionScoring::scorePosition(point, gen::LineOfSight, field, world).score < MINIMUM_LINE_OF_SIGHT) return false; diff --git a/roboteam_ai/src/stp/computations/PositionComputations.cpp b/roboteam_ai/src/stp/computations/PositionComputations.cpp index eea178727..1ab2d1628 100644 --- a/roboteam_ai/src/stp/computations/PositionComputations.cpp +++ b/roboteam_ai/src/stp/computations/PositionComputations.cpp @@ -91,8 +91,8 @@ std::vector PositionComputations::determineWallPositions(const rtt::Fie // If the ball has to be placed somewhere on the field, assume the ball is already there ballPos = GameStateManager::getRefereeDesignatedPosition(); } else if (field.leftDefenseArea.contains(ballPos)) { - // If the ball is in our defense area, project it out of it - ballPos = FieldComputations::projectPointOutOfDefenseArea(field, ballPos, true, false); + // move the ball in the direction of the ball speed, until it is outside the defense area + ballPos = FieldComputations::projectPointToValidPositionOnLine(field, ballPos, ballPos, ballPos + ball->velocity.stretchToLength(5), 0); } else if ((world->getWorld().value().getBall()->get()->velocity).length() > constants::BALL_GOT_SHOT_LIMIT && InterceptionComputations::calculateTheirBallInterception(world, ballTrajectory).has_value()) { ballPos = *InterceptionComputations::calculateTheirBallInterception(world, ballTrajectory); @@ -109,7 +109,8 @@ std::vector PositionComputations::determineWallPositions(const rtt::Fie // Find the intersection of the ball-to-goal line with the border of the defense area LineSegment ball2GoalLine = LineSegment(ballPos, field.leftGoalArea.rightLine().center()); - std::vector lineBorderIntersects = FieldComputations::getDefenseArea(field, true, extraLength.length(), 0).intersections(ball2GoalLine); + auto [theirDefenseAreaMargin, ourDefenseAreaMargin] = FieldComputations::getDefenseAreaMargin(); + std::vector lineBorderIntersects = FieldComputations::getDefenseArea(field, true, extraLength.length() + ourDefenseAreaMargin, 0).intersections(ball2GoalLine); // If the ball is in our defense area, project it outside, otherwise use the intersection with our defense area std::sort(lineBorderIntersects.begin(), lineBorderIntersects.end(), [](Vector2 a, Vector2 b) { return a.x > b.x; }); projectedPosition = lineBorderIntersects.front(); @@ -337,23 +338,23 @@ void PositionComputations::calculateInfoForHarasser(std::unordered_mapget()->getYaw(); auto harasserAngle = stpInfos["harasser"].getYaw(); // If enemy is not facing our goal AND does have the ball, stand between the enemy and our goal - if (enemyClosestToBall->get()->hasBall() && enemyAngle.shortestAngleDiff(harasserAngle) < M_PI / 1.5) { + LineSegment ourToBall = LineSegment(stpInfos["harasser"].getRobot()->get()->getPos(), world->getWorld()->getBall()->get()->position); + // project their point on the line + Vector2 projectedPoint = ourToBall.project(enemyClosestToBall->get()->getPos()); + bool theyAreBetween = (projectedPoint != world->getWorld()->getBall()->get()->position); + bool theyAreCloser = (enemyClosestToBall->get()->getPos() - world->getWorld()->getBall()->get()->position).length() < (stpInfos["harasser"].getRobot()->get()->getPos() - world->getWorld()->getBall()->get()->position).length(); + auto harasser = std::find_if(roles->begin(), roles->end(), [](const std::unique_ptr &role) { return role != nullptr && role->getName() == "harasser"; }); + if (theyAreBetween && theyAreCloser) { auto enemyPos = enemyClosestToBall->get()->getPos(); - auto targetPos = enemyPos + (field.leftGoalArea.leftLine().center() - enemyPos).stretchToLength(constants::ROBOT_RADIUS * 4); + auto targetPos = world->getWorld()->getBall()->get()->position - (enemyPos - world->getWorld()->getBall()->get()->position).stretchToLength(constants::ROBOT_RADIUS * 3); + if (harasser != roles->end()) { + harasser->get()->reset(); + } stpInfos["harasser"].setPositionToMoveTo(targetPos); stpInfos["harasser"].setYaw((world->getWorld()->getBall()->get()->position - targetPos).angle()); } else { - auto harasser = std::find_if(roles->begin(), roles->end(), [](const std::unique_ptr &role) { return role != nullptr && role->getName() == "harasser"; }); - if (harasser != roles->end() && !harasser->get()->finished() && strcmp(harasser->get()->getCurrentTactic()->getName(), "Formation") == 0) { - auto enemyPos = enemyClosestToBall->get()->getPos(); - auto targetPos = enemyPos + (world->getWorld()->getBall()->get()->position - enemyPos).stretchToLength(constants::ROBOT_RADIUS * 3); - // prevent the harasser from being stuck on the side of the enemy - if (enemyClosestToBall->get()->hasBall() && ((stpInfos["harasser"].getRobot()->get()->getPos() - targetPos).length() > constants::ROBOT_RADIUS)) { - stpInfos["harasser"].setPositionToMoveTo(targetPos); - stpInfos["harasser"].setYaw((world->getWorld()->getBall()->get()->position - targetPos).angle()); - } else { - harasser->get()->forceNextTactic(); - } + if (harasser != roles->end()) { + harasser->get()->forceLastTactic(); } } } diff --git a/roboteam_ai/src/stp/skills/OrbitAngular.cpp b/roboteam_ai/src/stp/skills/OrbitAngular.cpp index 9dcfa91fc..dc76a1de6 100644 --- a/roboteam_ai/src/stp/skills/OrbitAngular.cpp +++ b/roboteam_ai/src/stp/skills/OrbitAngular.cpp @@ -15,7 +15,7 @@ Status OrbitAngular::onUpdate(const StpInfo &info) noexcept { // Determine direction and speed factor int direction = yaw.rotateDirection(currentYaw) ? -1 : 1; - double speedFactor = std::clamp(currentYaw.shortestAngleDiff(yaw) * 2 * M_PI, 0.0, M_PI); + double speedFactor = std::clamp(currentYaw.shortestAngleDiff(yaw) * 1.4 * M_PI, 0.0, M_PI); // Calculate target angular velocity and normal vector double targetAngularVelocity = direction * speedFactor; @@ -27,17 +27,11 @@ Status OrbitAngular::onUpdate(const StpInfo &info) noexcept { // Construct the robot command command.id = robot->getId(); command.velocity = targetVelocity; - // Commented for the control code before the Schubert open on 3 April 2024. Possible wise to use again somewhere in the distant future. - // We could also switch to _just_ using yaw, as on all other places in the code. The magic numbers here might still need some love after testing irl. - // command.useAngularVelocity = true; - // command.targetAngularVelocity = targetAngularVelocity; - // command.yaw = yaw; // target yaw is angular velocity times the time step (1/60th of a second) in basestation // in simulator, we multiple by 1/2.5 because of how the simulator works and the pid controller is tuned if (rtt::GameSettings::getRobotHubMode() == rtt::net::RobotHubMode::BASESTATION) { - // TODO ROBOCUP 2024: FIX THIS - command.yaw = currentYaw + Angle(targetAngularVelocity * 1 / 15); + command.yaw = currentYaw + Angle(targetAngularVelocity * 1 / 6); } else { command.yaw = currentYaw + Angle(targetAngularVelocity * 1 / 2.5); } @@ -54,7 +48,7 @@ Status OrbitAngular::onUpdate(const StpInfo &info) noexcept { } // Check whether the robot has been within the margin - return (withinMarginCount > 3) ? Status::Success : Status::Running; + return (withinMarginCount > 0) ? Status::Success : Status::Running; } const char *OrbitAngular::getName() { return "OrbitAngular"; } diff --git a/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp b/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp index a82dd3918..0c5c64411 100644 --- a/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp +++ b/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp @@ -23,8 +23,6 @@ const double KEEPER_DISTANCE_TO_GOAL_LINE = constants::ROBOT_RADIUS * std::sin(t const double KEEPER_GOAL_DECREASE_AT_ONE_SIDE = constants::ROBOT_RADIUS * std::cos(toRadians(80.0)) + 0.01; // Plus a small margin to prevent keeper from crashing into goal // The maximum distance from the goal for when we say the ball is heading towards our goal constexpr double MAX_DISTANCE_HEADING_TOWARDS_GOAL = 0.2; -// For determining where the keeper should stand to stand between the ball and the goal, we draw a line from the ball to a bit behind the goal -constexpr double PROJECT_BALL_DISTANCE_TO_GOAL = 0.5; // Small means keeper will me more in center, big means keeper will be more to the side of the goal // We stop deciding where the keeper should be if the ball is too far behind our own goal constexpr double MAX_DISTANCE_BALL_BEHIND_GOAL = 0.1; @@ -43,21 +41,14 @@ std::optional KeeperBlockBall::calculateInfoForSkill(const StpInfo &inf skillStpInfo.setShouldAvoidOutOfField(std::get<1>(targetPosition)); skillStpInfo.setShouldAvoidOurRobots(std::get<1>(targetPosition)); skillStpInfo.setShouldAvoidTheirRobots(std::get<1>(targetPosition)); + skillStpInfo.setKickOrChip(KickType::CHIP); + skillStpInfo.setShotPower(ShotPower::MAX); + skillStpInfo.setShootOnFirstTouch(true); + skillStpInfo.setPositionToShootAt(Vector2(6, 0)); const auto yaw = calculateYaw(info.getBall().value(), std::get<0>(targetPosition)); - // TODO ROBOCUP 2024: MAKEW MORE PRETTY - const auto &field = info.getField().value(); - const auto &ball = info.getBall().value(); - const auto keepersLineSegment = getKeepersLineSegment(field); - const LineSegment ballTrajectory(ball->position, ball->expectedEndPosition); - bool ballHeadsTowardsOurGoal = ballTrajectory.intersects(keepersLineSegment).has_value(); - if (ballHeadsTowardsOurGoal) { - skillStpInfo.setYaw(skillStpInfo.getRobot()->get()->getYaw()); - } else { - skillStpInfo.setYaw(yaw); - } - + skillStpInfo.setYaw(yaw); skillStpInfo.setMaxJerk(std::get<2>(targetPosition)); return skillStpInfo; @@ -67,13 +58,7 @@ bool KeeperBlockBall::isEndTactic() noexcept { return true; } bool KeeperBlockBall::isTacticFailing(const StpInfo &) noexcept { return false; } -bool KeeperBlockBall::shouldTacticReset(const StpInfo &info) noexcept { - // const double errorMargin = constants::GO_TO_POS_ERROR_MARGIN * M_PI; - // const auto distanceToTarget = (info.getRobot().value()->getPos() - info.getPositionToMoveTo().value()).length(); - // return distanceToTarget > errorMargin; - // TODO ROBOCUP 2024: CHECK IF THIS IS LEGIT, or if we do need reset - return false; -} +bool KeeperBlockBall::shouldTacticReset(const StpInfo &info) noexcept { return false; } const char *KeeperBlockBall::getName() { return "Keeper Block Ball"; } @@ -97,10 +82,6 @@ std::tuple KeeperBlockBall::calculateTargetPosition(const const auto keepersLineSegment = getKeepersLineSegment(field); const LineSegment ballTrajectory(ball->position, ball->expectedEndPosition); bool ballHeadsTowardsOurGoal = ballTrajectory.intersects(keepersLineSegment).has_value(); - // TODO ROBOCUP 2024: CHECK AND PERHAPS MAKE MORE PRETTY - if (ballHeadsTowardsOurGoal && ballTrajectory.intersects(keepersLineSegment).value().dist(info.getRobot().value()->getPos()) < 0.03) { - return std::make_tuple(info.getRobot().value()->getPos(), false, 12); - } if (ballHeadsTowardsOurGoal) { auto shouldAvoidGoalPosts = false; @@ -139,15 +120,19 @@ std::pair KeeperBlockBall::calculateTargetPositionBallShot(cons const auto closestPointToGoal = Line(ballTrajectory).intersect(Line(keepersLineSegment)); // If possible, we intercept the ball at the line - if (closestPointToGoal.has_value()) { - const auto ballTimeAtClosestPoint = FieldComputations::getBallTimeAtPosition(*ball.get(), closestPointToGoal.value()); - auto [targetPosition, timeToTarget] = control::OvershootComputations::overshootingDestination(robotPosition, closestPointToGoal.value(), robotVelocity, maxRobotVelocity, - maxRobotAcceleration, ballTimeAtClosestPoint); - if (timeToTarget <= ballTimeAtClosestPoint) { - // TODO ROBOCUP 2024: TWEAK THIS VALUE - auto jerk = (1 - std::min((ballTimeAtClosestPoint - timeToTarget), 0.2) / 0.2) * 80 + ai::constants::MAX_JERK_DEFAULT; - return {targetPosition, jerk}; - } + // if (closestPointToGoal.has_value()) { + // const auto ballTimeAtClosestPoint = FieldComputations::getBallTimeAtPosition(*ball.get(), closestPointToGoal.value()); + // auto [targetPosition, timeToTarget] = control::OvershootComputations::overshootingDestination(robotPosition, closestPointToGoal.value(), robotVelocity, maxRobotVelocity, + // maxRobotAcceleration, ballTimeAtClosestPoint); + // if (timeToTarget <= ballTimeAtClosestPoint) { + // // TODO ROBOCUP 2024: TWEAK THIS VALUE + // auto jerk = (1 - std::min((ballTimeAtClosestPoint - timeToTarget), 0.2) / 0.2) * 160 + ai::constants::MAX_JERK_DEFAULT; + // return {targetPosition, jerk}; + // } + // } + // if we are at most 0.03m away, set target to the closest point + if (closestPointToGoal.has_value() && (closestPointToGoal.value() - robotPosition).length() <= 0.03) { + return {closestPointToGoal.value(), ai::constants::MAX_JERK_DEFAULT}; } double maxTimeLeftWhenArrived = std::numeric_limits::lowest(); @@ -168,8 +153,7 @@ std::pair KeeperBlockBall::calculateTargetPositionBallShot(cons if (timeLeftWhenArrived > maxTimeLeftWhenArrived) { maxTimeLeftWhenArrived = timeLeftWhenArrived; optimalTarget = currentTarget; - // TODO ROBOCUP 2024: TWEAK THIS VALUE - jerk = (1 - std::min(std::max(timeLeftWhenArrived, 0.0), 0.2) / 0.2) * 80 + ai::constants::MAX_JERK_DEFAULT; + jerk = (1 - std::min(std::max(timeLeftWhenArrived, 0.0), 0.2) / 0.2) * 160 + ai::constants::MAX_JERK_DEFAULT; } } return {optimalTarget, jerk}; @@ -243,7 +227,7 @@ Vector2 KeeperBlockBall::calculateTargetPositionBallNotShot(const StpInfo &info, Angle KeeperBlockBall::calculateYaw(const world::view::BallView &ball, const Vector2 &targetKeeperPosition) { // Look towards ball to ensure ball hits the front assembly to reduce odds of ball reflecting in goal const auto keeperToBall = (ball->position - targetKeeperPosition); - return keeperToBall.angle() / 1.3; + return keeperToBall.angle(); } } // namespace rtt::ai::stp::tactic diff --git a/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp b/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp index 4e2d2a96a..a81e5a24e 100644 --- a/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp +++ b/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp @@ -22,11 +22,7 @@ std::optional DriveWithBall::calculateInfoForSkill(const StpInfo &info) bool DriveWithBall::isTacticFailing(const StpInfo &info) noexcept { return !info.getRobot().value()->hasBall() || !info.getPositionToMoveTo(); } -bool DriveWithBall::shouldTacticReset(const StpInfo &info) noexcept { - // return skills.current_num() == 1 && info.getRobot()->get()->getYaw().shortestAngleDiff(info.getYaw()) > constants::HAS_BALL_ANGLE; - // TODO ROBOCUP 2024: CHECK IF WE NEED THAT LINE - return false; -} +bool DriveWithBall::shouldTacticReset(const StpInfo &info) noexcept { return false; } bool DriveWithBall::isEndTactic() noexcept { return false; } diff --git a/roboteam_ai/src/stp/tactics/active/GetBall.cpp b/roboteam_ai/src/stp/tactics/active/GetBall.cpp index 6a48ca794..c100e2334 100644 --- a/roboteam_ai/src/stp/tactics/active/GetBall.cpp +++ b/roboteam_ai/src/stp/tactics/active/GetBall.cpp @@ -31,13 +31,6 @@ std::optional GetBall::calculateInfoForSkill(const StpInfo &info) noexc Vector2 interceptionPosition = interceptionInfo.interceptLocation; Vector2 interceptionVelocity = interceptionInfo.interceptVelocity; - // TODO ROBOCUP 2024: CHECK IF NEEDED for ball placer - // auto maxRobotVelocity = GameStateManager::getCurrentGameState().getRuleSet().getMaxRobotVel(); - // if (info.getRobot()->get()->hasBall()) { - // maxRobotVelocity = std::clamp(info.getBall().value()->velocity.length() * 0.8, 0.5, maxRobotVelocity); - // skillStpInfo.setMaxRobotVelocity(maxRobotVelocity); - // } - double distanceToInterception = (interceptionPosition - robotPosition).length(); double distanceToBall = (ballPosition - robotPosition).length(); @@ -49,17 +42,11 @@ std::optional GetBall::calculateInfoForSkill(const StpInfo &info) noexc if (info.getRobot()->get()->getAngleDiffToBall() > constants::HAS_BALL_ANGLE && distanceToBall < constants::ROBOT_CLOSE_TO_POINT) { skillStpInfo.setPositionToMoveTo(info.getRobot()->get()->getPos()); skillStpInfo.setTargetVelocity(Vector2(0, 0)); - } else if (info.getBall()->get()->velocity.length() > constants::BALL_IS_MOVING_SLOW_LIMIT) { - auto newRobotPos = interceptionPosition + (interceptionPosition - ballPosition).stretchToLength(constants::CENTER_TO_FRONT); - skillStpInfo.setPositionToMoveTo(newRobotPos); - skillStpInfo.setTargetVelocity(interceptionVelocity); } else { - auto getBallDistance = std::max(distanceToInterception - constants::CENTER_TO_FRONT, MIN_DISTANCE_TO_TARGET); - Vector2 newRobotPosition = robotPosition + (interceptionPosition - robotPosition).stretchToLength(getBallDistance); - newRobotPosition = FieldComputations::projectPointToValidPosition(info.getField().value(), newRobotPosition, info.getObjectsToAvoid()); - skillStpInfo.setPositionToMoveTo(newRobotPosition); + skillStpInfo.setPositionToMoveTo(interceptionPosition); skillStpInfo.setTargetVelocity(interceptionVelocity); } + skillStpInfo.setMaxJerk(constants::MAX_JERK_DEFAULT); skillStpInfo.setYaw((ballPosition - robotPosition).angle()); diff --git a/roboteam_ai/src/stp/tactics/active/Receive.cpp b/roboteam_ai/src/stp/tactics/active/Receive.cpp index 0fe09680a..d8d1ad6ca 100644 --- a/roboteam_ai/src/stp/tactics/active/Receive.cpp +++ b/roboteam_ai/src/stp/tactics/active/Receive.cpp @@ -21,12 +21,7 @@ std::optional Receive::calculateInfoForSkill(StpInfo const &info) noexc bool Receive::isTacticFailing(const StpInfo &info) noexcept { return !info.getPositionToMoveTo(); } -bool Receive::shouldTacticReset(const StpInfo &info) noexcept { - // double errorMargin = constants::GO_TO_POS_ERROR_MARGIN * M_PI; - // return (info.getRobot().value()->getPos() - info.getPositionToMoveTo().value()).length() > errorMargin; - // TODO ROBOCUP 2024: CHECK IF NEEDED - return false; -} +bool Receive::shouldTacticReset(const StpInfo &info) noexcept { return false; } bool Receive::isEndTactic() noexcept { return true; } diff --git a/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp b/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp index b05577d59..c3e1affdd 100644 --- a/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp +++ b/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp @@ -6,7 +6,7 @@ namespace rtt::ai::stp::tactic { const int STAND_STILL_THRESHOLD = 60; -const int MOVE_AFTER_DRIBBLER_OFF = 20; +const int MOVE_AFTER_DRIBBLER_OFF = 60; BallStandBack::BallStandBack() { skills = rtt::collections::state_machine{skill::GoToPos()}; } @@ -19,6 +19,8 @@ std::optional BallStandBack::calculateInfoForSkill(StpInfo const &info) Vector2 ballTarget = info.getBall()->get()->position; auto robot = info.getRobot()->get(); if (standStillCounter > STAND_STILL_THRESHOLD) { + skillStpInfo.setMaxRobotVelocity(0.5); + skillStpInfo.setMaxJerk(1); skillStpInfo.setDribblerOn(false); if (standStillCounter > STAND_STILL_THRESHOLD + MOVE_AFTER_DRIBBLER_OFF) { auto moveVector = robot->getPos() - ballTarget; diff --git a/roboteam_ai/src/world/FieldComputations.cpp b/roboteam_ai/src/world/FieldComputations.cpp index ebc97442a..0215b1c84 100644 --- a/roboteam_ai/src/world/FieldComputations.cpp +++ b/roboteam_ai/src/world/FieldComputations.cpp @@ -9,15 +9,15 @@ namespace rtt::ai { std::tuple FieldComputations::getDefenseAreaMargin() { - double theirDefenseAreaMargin = constants::ROBOT_RADIUS + constants::GO_TO_POS_ERROR_MARGIN; - double ourDefenseAreaMargin = -constants::ROBOT_RADIUS + constants::GO_TO_POS_ERROR_MARGIN; + double theirDefenseAreaMargin = constants::ROBOT_RADIUS * 1.4 + constants::GO_TO_POS_ERROR_MARGIN; + double ourDefenseAreaMargin = -constants::ROBOT_RADIUS * 0.9 + constants::GO_TO_POS_ERROR_MARGIN; RuleSetName ruleSetTitle = GameStateManager::getCurrentGameState().getRuleSet().getTitle(); RefCommand currentGameState = GameStateManager::getCurrentGameState().getCommandId(); if (ruleSetTitle == RuleSetName::STOP || currentGameState == RefCommand::DIRECT_FREE_THEM || currentGameState == RefCommand::KICKOFF_THEM || currentGameState == RefCommand::DIRECT_FREE_US) { - theirDefenseAreaMargin += 0.2; + theirDefenseAreaMargin += 0.3; } return std::make_tuple(theirDefenseAreaMargin, ourDefenseAreaMargin); diff --git a/roboteam_ai/src/world/WorldData.cpp b/roboteam_ai/src/world/WorldData.cpp index 6dd4ad9ca..9a7dec856 100644 --- a/roboteam_ai/src/world/WorldData.cpp +++ b/roboteam_ai/src/world/WorldData.cpp @@ -26,15 +26,15 @@ WorldData::WorldData(const World *data, proto::World &protoMsg) noexcept : time{ // } for (auto &each : ours) { - if (isnan(each.pos().x())) { - RTT_ERROR("WATCH OUT! ROBOT WITH NAN VALUES RECEIVED FROM OBSERVER! Omitting robot for now..") + if (!isfinite(each.pos().x()) || !isfinite(each.pos().y()) || !isfinite(each.vel().x()) || !isfinite(each.vel().y()) || !isfinite(each.yaw()) || !isfinite(each.w())) { + RTT_ERROR("WATCH OUT! ROBOT WITH NAN OR INFINITE POSITION/VELOCITY/YAW/W VALUES RECEIVED FROM OBSERVER! Omitting robot for now.."); } else { robots.emplace_back(each, Team::us, getBall()); } } for (auto &each : others) { - if (isnan(each.pos().x())) { - RTT_ERROR("WATCH OUT! ROBOT WITH NAN VALUES RECEIVED FROM OBSERVER! Omitting robot for now..") + if (!isfinite(each.pos().x()) || !isfinite(each.pos().y()) || !isfinite(each.vel().x()) || !isfinite(each.vel().y()) || !isfinite(each.yaw()) || !isfinite(each.w())) { + RTT_ERROR("WATCH OUT! ROBOT WITH NAN OR INFINITE POSITION/VELOCITY/YAW/W VALUES RECEIVED FROM OBSERVER! Omitting robot for now.."); } else { robots.emplace_back(each, Team::them, getBall()); } diff --git a/roboteam_observer/observer/include/observer/filters/vision/WorldFilter.h b/roboteam_observer/observer/include/observer/filters/vision/WorldFilter.h index 2ed7658cf..f2bc3367c 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/WorldFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/WorldFilter.h @@ -26,7 +26,7 @@ class WorldFilter { void process(const std::vector& frames, const std::vector& feedback, const std::vector& camera_ids); - [[nodiscard]] proto::World getWorldPrediction(const Time& time) const; + [[nodiscard]] proto::World getWorldPrediction(const Time& time); void updateRobotParameters(const TwoTeamRobotParameters& robotInfo); @@ -50,8 +50,8 @@ class WorldFilter { void processBalls(const DetectionFrame& frame); [[nodiscard]] std::vector getHealthiestRobotsMerged(bool blueBots, Time time) const; [[nodiscard]] std::vector oneCameraHealthyRobots(bool blueBots, int camera_id, Time time) const; - void addRobotPredictionsToMessage(proto::World& world, Time time) const; - void addBallPredictionsToMessage(proto::World& world, Time time) const; + void addRobotPredictionsToMessage(proto::World& world, Time time); + void addBallPredictionsToMessage(proto::World& world, Time time); // take care, although these method are static, they typically DO modify the current object as they have a robotMap reference static void predictRobots(const DetectionFrame& frame, robotMap& robots); diff --git a/roboteam_observer/observer/include/observer/filters/vision/ball/BallFilter.h b/roboteam_observer/observer/include/observer/filters/vision/ball/BallFilter.h index 1fad5ecb0..1bef5516b 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/ball/BallFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/ball/BallFilter.h @@ -28,7 +28,7 @@ class BallFilter { * @param until Time to predict the ball at * @return The prediction */ - [[nodiscard]] GroundBallPrediction predictCam(int cameraID, Time until) const; + [[nodiscard]] GroundBallPrediction predictCam(int cameraID, Time until, std::vector yellowRobots, std::vector blueRobots); /** * Updates the ground filter with a given camera ID with Prediction Observation pairs. @@ -49,6 +49,11 @@ class BallFilter { */ [[nodiscard]] double getHealth() const; + /** + * @return The number of observations the filter has seen + */ + [[nodiscard]] double getNumObservations() const; + private: std::map groundFilters; }; diff --git a/roboteam_observer/observer/include/observer/filters/vision/ball/CameraGroundBallFilter.h b/roboteam_observer/observer/include/observer/filters/vision/ball/CameraGroundBallFilter.h index 2290181d5..d99c5aab7 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/ball/CameraGroundBallFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/ball/CameraGroundBallFilter.h @@ -6,6 +6,7 @@ #include "FilteredBall.h" #include "GroundBallExtendedKalmanFilter.h" #include "observer/filters/vision/CameraObjectFilter.h" +#include "observer/filters/vision/robot/FilteredRobot.h" struct CameraGroundBallPrediction { CameraGroundBallPrediction() = default; @@ -24,11 +25,12 @@ class CameraGroundBallFilter : public CameraObjectFilter { [[nodiscard]] FilteredBall getEstimate(Time time) const; [[nodiscard]] Eigen::Vector2d getVelocityEstimate(Time time) const; - [[nodiscard]] CameraGroundBallPrediction predict(Time time) const; - + [[nodiscard]] CameraGroundBallPrediction predict(Time time, std::vector yellowRobots, std::vector blueRobots); bool processDetections(const CameraGroundBallPredictionObservationPair& prediction_observation_pair); private: + bool checkRobots(const std::vector& robots, const Eigen::Vector2d& positionEstimate, const Eigen::Vector2d& velocityEstimate); + bool checkRobotCollision(const FilteredRobot& robot, const Eigen::Vector2d& positionEstimate, const Eigen::Vector2d& velocityEstimate); void predictFilter(const CameraGroundBallPrediction& prediction); void update(const BallObservation& observation); bool updateNotSeen(Time time); diff --git a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotFilter.h b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotFilter.h index 1ef87a9df..484f185fd 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotFilter.h @@ -30,6 +30,7 @@ class RobotFilter { bool processNotSeen(int cameraID, const Time& time); [[nodiscard]] double getHealth() const; + [[nodiscard]] size_t getNumObservations() const; /** * @brief Merges robot estimates from different cameras into a single robot estimate * @param time to estimate the robot position at diff --git a/roboteam_observer/observer/src/filters/vision/DetectionFrame.cpp b/roboteam_observer/observer/src/filters/vision/DetectionFrame.cpp index d35e5e288..47f2af1f9 100644 --- a/roboteam_observer/observer/src/filters/vision/DetectionFrame.cpp +++ b/roboteam_observer/observer/src/filters/vision/DetectionFrame.cpp @@ -2,12 +2,23 @@ DetectionFrame::DetectionFrame(const proto::SSL_DetectionFrame& protoFrame) : cameraID(protoFrame.camera_id()), timeCaptured{protoFrame.t_capture()}, timeSent{protoFrame.t_sent()} { for (const auto& ball : protoFrame.balls()) { + // If you only want to use one side, uncomment this + // Might be nice to move to inputs + // if (ball.x() < 0) { + // continue; + // } balls.emplace_back(BallObservation(cameraID, timeCaptured, timeSent, ball)); } for (const auto& blueBot : protoFrame.robots_blue()) { + // if (blueBot.x() < 0) { + // continue; + // } blue.emplace_back(RobotObservation(cameraID, timeCaptured, timeSent, TeamColor::BLUE, blueBot)); } for (const auto& yellowBot : protoFrame.robots_yellow()) { + // if (yellowBot.x() < 0) { + // continue; + // } yellow.emplace_back(RobotObservation(cameraID, timeCaptured, timeSent, TeamColor::YELLOW, yellowBot)); } } \ No newline at end of file diff --git a/roboteam_observer/observer/src/filters/vision/WorldFilter.cpp b/roboteam_observer/observer/src/filters/vision/WorldFilter.cpp index d68005b0d..dfbc38212 100644 --- a/roboteam_observer/observer/src/filters/vision/WorldFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/WorldFilter.cpp @@ -3,7 +3,51 @@ #include "filters/vision/ball/BallAssigner.h" WorldFilter::WorldFilter() {} -proto::World WorldFilter::getWorldPrediction(const Time &time) const { +bool botHasNonsensicalValue(const proto::WorldRobot &bot) { + double xPos = bot.pos().x(); + double yPos = bot.pos().y(); + + for (const double value : {xPos, yPos}) { + if (std::isnan(value) || std::isinf(value) || value < -10 || value > 10) { + return true; + } + } + double xVel = bot.vel().x(); + double yVel = bot.vel().y(); + for (const double value : {xVel, yVel}) { + if (std::isnan(value) || std::isinf(value) || value < -20 || value > 20) { + return true; + } + } + if (bot.yaw() > 2 * M_PI || bot.yaw() < -2 * M_PI) { + return true; + } + if (bot.w() > 20 * M_PI || bot.w() < -20 * M_PI) { + return true; + } + return false; +} + +bool ballHasNonsensicalValue(const proto::WorldBall &ball) { + double xPos = ball.pos().x(); + double yPos = ball.pos().y(); + + for (const double value : {xPos, yPos}) { + if (std::isnan(value) || std::isinf(value) || value < -10 || value > 10) { + return true; + } + } + double xVel = ball.vel().x(); + double yVel = ball.vel().y(); + for (const double value : {xVel, yVel}) { + if (std::isnan(value) || std::isinf(value) || value < -20 || value > 20) { + return true; + } + } + return false; +} + +proto::World WorldFilter::getWorldPrediction(const Time &time) { proto::World world; addRobotPredictionsToMessage(world, time); addBallPredictionsToMessage(world, time); @@ -113,6 +157,11 @@ std::vector WorldFilter::getHealthiestRobotsMerged(bool blueBots, continue; ; } + bool allSmall = std::all_of(oneIDFilters.second.begin(), oneIDFilters.second.end(), [](const RobotFilter &filter) { return filter.getNumObservations() <= 3; }); + if (allSmall) { + continue; + } + double maxHealth = -std::numeric_limits::infinity(); auto bestFilter = oneIDFilters.second.begin(); for (auto robotFilter = oneIDFilters.second.begin(); robotFilter != oneIDFilters.second.end(); ++robotFilter) { @@ -151,11 +200,16 @@ std::vector WorldFilter::oneCameraHealthyRobots(bool blueBots, in } return robots; } -void WorldFilter::addRobotPredictionsToMessage(proto::World &world, Time time) const { +void WorldFilter::addRobotPredictionsToMessage(proto::World &world, Time time) { auto feedbackBots = feedbackFilter.getRecentFeedback(); std::vector blueRobots = getHealthiestRobotsMerged(true, time); + int blueCount = 0; for (const auto &blueBot : blueRobots) { + if (blueCount >= 11) { + break; // Only 11 robots per team, if vision is bad, we might have more robots, making ai crash + } + blueCount++; auto worldBot = blueBot.asWorldRobot(); auto feedback_it = std::find_if(feedbackBots.begin(), feedbackBots.end(), [&](const std::pair &bot) { return bot.first.team == TeamColor::BLUE && bot.first.robot_id == RobotID(worldBot.id()); @@ -164,10 +218,20 @@ void WorldFilter::addRobotPredictionsToMessage(proto::World &world, Time time) c worldBot.mutable_feedbackinfo()->CopyFrom(feedback_it->second); feedbackBots.erase(feedback_it); } - world.mutable_blue()->Add()->CopyFrom(worldBot); + if (botHasNonsensicalValue(worldBot)) { + std::cout << "Nonsense values detected for blue " << worldBot.id() << ", resetting all its filters!!\n"; + blue[RobotID(world.id())].clear(); // Nuclear, simply remove all robot filters for this robot... + } else { + world.mutable_blue()->Add()->CopyFrom(worldBot); + } } std::vector yellowRobots = getHealthiestRobotsMerged(false, time); + int yellowCount = 0; for (const auto &yellowBot : yellowRobots) { + if (yellowCount >= 11) { + break; // Only 11 robots per team, if vision is bad, we might have more robots, making ai crash + } + yellowCount++; auto worldBot = yellowBot.asWorldRobot(); auto feedback_it = std::find_if(feedbackBots.begin(), feedbackBots.end(), [&](const std::pair &bot) { return bot.first.team == TeamColor::YELLOW && bot.first.robot_id == RobotID(worldBot.id()); @@ -176,7 +240,12 @@ void WorldFilter::addRobotPredictionsToMessage(proto::World &world, Time time) c worldBot.mutable_feedbackinfo()->CopyFrom(feedback_it->second); feedbackBots.erase(feedback_it); } - world.mutable_yellow()->Add()->CopyFrom(worldBot); + if (botHasNonsensicalValue(worldBot)) { + std::cout << "Nonsense values detected for yellow " << worldBot.id() << ", resetting all its filters!!\n"; + yellow[RobotID(world.id())].clear(); // Nuclear, simply remove all robot filters for this robot... + } else { + world.mutable_yellow()->Add()->CopyFrom(worldBot); + } } // Any remaining feedback of robots is put into the lonely category for (const auto &bot : feedbackBots) { @@ -188,9 +257,11 @@ void WorldFilter::addRobotPredictionsToMessage(proto::World &world, Time time) c } void WorldFilter::processBalls(const DetectionFrame &frame) { std::vector predictions(balls.size()); + std::vector blueRobots = getHealthiestRobotsMerged(true, frame.timeCaptured); + std::vector yellowRobots = getHealthiestRobotsMerged(false, frame.timeCaptured); // get predictions from cameras for (std::size_t i = 0; i < balls.size(); ++i) { - predictions[i] = balls[i].predictCam(frame.cameraID, frame.timeCaptured).prediction; + predictions[i] = balls[i].predictCam(frame.cameraID, frame.timeCaptured, yellowRobots, blueRobots).prediction; } // assign observations to relevant filters BallAssignmentResult assignment = BallAssigner::assign_balls(predictions, frame.balls); @@ -209,12 +280,27 @@ void WorldFilter::processBalls(const DetectionFrame &frame) { balls.emplace_back(BallFilter(newBall)); } } -void WorldFilter::addBallPredictionsToMessage(proto::World &world, Time time) const { - if (!balls.empty()) { - auto bestFilter = std::max_element(balls.begin(), balls.end(), [](const BallFilter &best, const BallFilter &filter) { return best.getHealth() < filter.getHealth(); }); - - FilteredBall bestBall = bestFilter->mergeBalls(time); - - world.mutable_ball()->CopyFrom(bestBall.asWorldBall()); +void WorldFilter::addBallPredictionsToMessage(proto::World &world, Time time) { + const BallFilter *bestFilter = nullptr; + double bestHealth = -1.0; + for (auto &filter : balls) { + if (filter.getNumObservations() > 3) { + double currentHealth = filter.getHealth(); + if (!bestFilter || currentHealth > bestHealth) { + bestFilter = &filter; + bestHealth = currentHealth; + } + } + } + if (!bestFilter) { + return; + } + FilteredBall bestBall = bestFilter->mergeBalls(time); + auto protoBall = bestBall.asWorldBall(); + if (ballHasNonsensicalValue(protoBall)) { + std::cout << "Nonsense values detected for the ball, nuking all ball filters...\n"; + balls.clear(); + } else { + world.mutable_ball()->CopyFrom(protoBall); } } diff --git a/roboteam_observer/observer/src/filters/vision/ball/BallFilter.cpp b/roboteam_observer/observer/src/filters/vision/ball/BallFilter.cpp index c68e0f25f..615ca12c6 100644 --- a/roboteam_observer/observer/src/filters/vision/ball/BallFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/ball/BallFilter.cpp @@ -3,10 +3,10 @@ #include BallFilter::BallFilter(const BallObservation &observation) : groundFilters{std::make_pair(observation.cameraID, CameraGroundBallFilter(observation))} {} -GroundBallPrediction BallFilter::predictCam(int cameraID, Time until) const { +GroundBallPrediction BallFilter::predictCam(int cameraID, Time until, std::vector yellowRobots, std::vector blueRobots) { auto camera_filter = groundFilters.find(cameraID); if (camera_filter != groundFilters.end()) { - GroundBallPrediction prediction(camera_filter->second.predict(until), true); + GroundBallPrediction prediction(camera_filter->second.predict(until, yellowRobots, blueRobots), true); return prediction; } // no information for this camera available; we merge data from available camera's @@ -63,5 +63,12 @@ double BallFilter::getHealth() const { } return maxHealth; } +double BallFilter::getNumObservations() const { + double maxTotalObservations = 0.0; + for (const auto &filter : groundFilters) { + maxTotalObservations = fmax(filter.second.numObservations(), maxTotalObservations); + } + return maxTotalObservations; +} GroundBallPrediction::GroundBallPrediction(CameraGroundBallPrediction prediction, bool hadRequestedCamera) : prediction{std::move(prediction)}, hadRequestedCamera{hadRequestedCamera} {} diff --git a/roboteam_observer/observer/src/filters/vision/ball/CameraGroundBallFilter.cpp b/roboteam_observer/observer/src/filters/vision/ball/CameraGroundBallFilter.cpp index 436b0882e..ad330dd72 100644 --- a/roboteam_observer/observer/src/filters/vision/ball/CameraGroundBallFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/ball/CameraGroundBallFilter.cpp @@ -1,8 +1,9 @@ #include +#include #include -void CameraGroundBallFilter::update(const BallObservation &observation) { +void CameraGroundBallFilter::update(const BallObservation& observation) { ekf.update(observation.position); objectSeen(observation.timeCaptured); } @@ -10,7 +11,7 @@ bool CameraGroundBallFilter::updateNotSeen(Time time) { objectInvisible(time); return getHealth() <= 0.0 && consecutiveFramesNotSeen() >= 3; } -bool CameraGroundBallFilter::processDetections(const CameraGroundBallPredictionObservationPair &prediction_observation_pair) { +bool CameraGroundBallFilter::processDetections(const CameraGroundBallPredictionObservationPair& prediction_observation_pair) { predictFilter(prediction_observation_pair.prediction); bool removeFilter = false; if (prediction_observation_pair.observation.has_value()) { @@ -20,12 +21,12 @@ bool CameraGroundBallFilter::processDetections(const CameraGroundBallPredictionO } return removeFilter; } -void CameraGroundBallFilter::predictFilter(const CameraGroundBallPrediction &prediction) { +void CameraGroundBallFilter::predictFilter(const CameraGroundBallPrediction& prediction) { // simple function for now but may become complicated with collisions ekf.predict(prediction.time); } Eigen::Vector2d CameraGroundBallFilter::getVelocityEstimate(Time time) const { return ekf.getVelocityEstimate(time); } -CameraGroundBallFilter::CameraGroundBallFilter(const BallObservation &observation, const Eigen::Vector2d &velocity_estimate) +CameraGroundBallFilter::CameraGroundBallFilter(const BallObservation& observation, const Eigen::Vector2d& velocity_estimate) : CameraObjectFilter(0.2, 1 / 60.0, 15, 3, observation.timeCaptured) { Eigen::Vector4d startState = {observation.position.x(), observation.position.y(), velocity_estimate.x(), velocity_estimate.y()}; Eigen::Matrix4d startCovariance = Eigen::Matrix4d::Zero(); @@ -41,11 +42,80 @@ CameraGroundBallFilter::CameraGroundBallFilter(const BallObservation &observatio constexpr double BALL_MEASUREMENT_ERROR = 0.002; //[m] estimated average position uncertainty in ball detections ekf = GroundBallExtendedKalmanFilter(startState, startCovariance, BALL_MODEL_ERROR, BALL_MEASUREMENT_ERROR, observation.timeCaptured); } -CameraGroundBallPrediction CameraGroundBallFilter::predict(Time time) const { - const auto &estimate = ekf.getStateEstimate(time); +CameraGroundBallPrediction CameraGroundBallFilter::predict(Time time, std::vector yellowRobots, std::vector blueRobots) { + auto positionEstimate = ekf.getPositionEstimate(time); + auto velocityEstimate = ekf.getVelocityEstimate(time); + + // Checkrobots also alters the ekf if there is a collision + if (!checkRobots(yellowRobots, positionEstimate, velocityEstimate)) { + checkRobots(blueRobots, positionEstimate, velocityEstimate); + } + const auto& estimate = ekf.getStateEstimate(time); CameraGroundBallPrediction prediction(estimate.head<2>(), estimate.tail<2>(), time); return prediction; } +bool CameraGroundBallFilter::checkRobots(const std::vector& robots, const Eigen::Vector2d& positionEstimate, const Eigen::Vector2d& velocityEstimate) { + for (const auto& robot : robots) { + if (checkRobotCollision(robot, positionEstimate, velocityEstimate)) { + return true; + } + } + return false; +} + +bool CameraGroundBallFilter::checkRobotCollision(const FilteredRobot& robot, const Eigen::Vector2d& positionEstimate, const Eigen::Vector2d& velocityEstimate) { + // assumed robot radius of 0.08m and center to front of 0.06m. That's on the low side, but should make sure we are safe + rtt::Vector2 robotPos = rtt::Vector2(robot.position.position.x(), robot.position.position.y()); + rtt::Angle robotYaw = rtt::Angle(robot.position.yaw); + rtt::Vector2 ballPos = rtt::Vector2(positionEstimate.x(), positionEstimate.y()); + rtt::Vector2 ballVel = rtt::Vector2(velocityEstimate.x(), velocityEstimate.y()); + rtt::Vector2 robotVel = rtt::Vector2(robot.velocity.velocity.x(), robot.velocity.velocity.y()); + + if (!rtt::RobotShape(robotPos, 0.05, 0.07, robotYaw).contains(ballPos)) { + return false; + } + + auto ballVelUsed = ballVel - robotVel; + auto robotShape = rtt::RobotShape(robotPos, 0.05 + 0.0213, 0.07 + 0.0213, robotYaw); + auto frontLine = robotShape.kicker(); + auto ballVelLine = rtt::LineSegment(ballPos, ballPos - ballVelUsed.stretchToLength(0.09 * 5)); + + if (frontLine.intersects(ballVelLine)) { + auto collisionAngle = (robotYaw - rtt::Angle(ballVelUsed.scale(-1))); + + if (std::abs(collisionAngle) > 0.5 * M_PI) { + return false; + } + + auto outVelAbs = ballVelUsed.length() - (ballVelUsed.length() * std::cos(collisionAngle) * 1); + auto outVel = rtt::Vector2(robotYaw).scale(-1).rotate(collisionAngle).scale(-1).stretchToLength(outVelAbs); + outVel += robotVel; + Eigen::Vector2d outVelEigen(outVel.x, outVel.y); + ekf.setVelocity(outVelEigen); + return true; + } + + auto botCircle = rtt::Circle(robotPos, 0.07 + 0.0213); + auto intersects = botCircle.intersects(ballVelLine); + + if (!intersects.empty()) { + auto intersect = intersects[0]; + auto collisionAngle = (rtt::Vector2(robotPos - intersect).toAngle() - ballVelUsed.toAngle()); + + if (std::abs(collisionAngle) > 0.5 * M_PI) { + return false; + } + + auto outVelAbs = ballVelUsed.length() - (ballVelUsed.length() * std::cos(collisionAngle) * 0.6); + auto outVel = rtt::Vector2(robotPos - intersect).rotate(collisionAngle).scale(-1).stretchToLength(outVelAbs); + outVel += robotVel; + Eigen::Vector2d outVelEigen(outVel.x, outVel.y); + ekf.setVelocity(outVelEigen); + return true; + } + + return false; +} FilteredBall CameraGroundBallFilter::getEstimate(Time time) const { FilteredBall ball(ekf.getPositionEstimate(time), ekf.getVelocityEstimate(time), getHealth(), ekf.getPositionUncertainty().norm(), ekf.getVelocityUncertainty().norm()); return ball; diff --git a/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp b/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp index cf20a7438..51bbb6263 100644 --- a/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp @@ -58,6 +58,13 @@ double RobotFilter::getHealth() const { } return maxHealth; } +size_t RobotFilter::getNumObservations() const { + size_t numObservations = 0.0; + for (const auto &filter : cameraFilters) { + numObservations += filter.second.numObservations(); + } + return numObservations; +} FilteredRobot RobotFilter::mergeRobots(const Time &time) const { double mergeFactor = 1.5; Eigen::Vector2d vel(0, 0); diff --git a/roboteam_observer/src/Handler.cpp b/roboteam_observer/src/Handler.cpp index 14ebf7892..b20b814f6 100644 --- a/roboteam_observer/src/Handler.cpp +++ b/roboteam_observer/src/Handler.cpp @@ -116,7 +116,7 @@ void Handler::start(std::string visionip, std::string refereeip, int visionport, } } }, - 100); + 80); } bool Handler::initializeNetworkers() { this->worldPublisher = std::make_unique(); @@ -202,7 +202,9 @@ void Handler::startReplay(rtt::LogFileReader& reader) { auto check = observer.process(visionPackets, refereePackets, feedbackPackets); numMessagesProcessed++; - std::cout << "Num Messages processed: " << numMessagesProcessed << "\n"; + if (numMessagesProcessed % 1000 == 0) { + std::cout << "Num Messages processed: " << numMessagesProcessed << "\n"; + } } }