2021-01-16 20:41:47 -08:00
|
|
|
/*
|
2022-01-20 19:35:28 -08:00
|
|
|
* MIT License
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2023-04-18 18:49:40 -04:00
|
|
|
* Copyright (c) PhotonVision
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2022-01-20 19:35:28 -08:00
|
|
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
|
|
|
|
* of this software and associated documentation files (the "Software"), to deal
|
|
|
|
|
* in the Software without restriction, including without limitation the rights
|
|
|
|
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
|
|
|
|
* copies of the Software, and to permit persons to whom the Software is
|
|
|
|
|
* furnished to do so, subject to the following conditions:
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2022-01-20 19:35:28 -08:00
|
|
|
* The above copyright notice and this permission notice shall be included in all
|
|
|
|
|
* copies or substantial portions of the Software.
|
|
|
|
|
*
|
|
|
|
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
|
|
|
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
|
|
|
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
|
|
|
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
|
|
|
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
|
|
|
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
|
|
|
|
* SOFTWARE.
|
2021-01-16 20:41:47 -08:00
|
|
|
*/
|
2022-01-20 19:35:28 -08:00
|
|
|
|
2022-12-16 17:05:23 -08:00
|
|
|
package frc.robot;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
import static frc.robot.Constants.Vision.*;
|
|
|
|
|
|
|
|
|
|
import frc.robot.subsystems.drivetrain.SwerveDrive;
|
2021-01-16 20:41:47 -08:00
|
|
|
import org.photonvision.PhotonCamera;
|
2025-12-29 16:16:56 -05:00
|
|
|
import org.wpilib.driverstation.XboxController;
|
|
|
|
|
import org.wpilib.math.geometry.Pose2d;
|
|
|
|
|
import org.wpilib.math.geometry.Rotation2d;
|
|
|
|
|
import org.wpilib.opmode.TimedRobot;
|
|
|
|
|
import org.wpilib.simulation.BatterySim;
|
|
|
|
|
import org.wpilib.simulation.RoboRioSim;
|
|
|
|
|
import org.wpilib.smartdashboard.SmartDashboard;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
|
|
|
|
public class Robot extends TimedRobot {
|
2024-09-14 23:10:02 -05:00
|
|
|
private SwerveDrive drivetrain;
|
|
|
|
|
private VisionSim visionSim;
|
|
|
|
|
private PhotonCamera camera;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
private final double VISION_TURN_kP = 0.01;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
private XboxController controller;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
@Override
|
|
|
|
|
public void robotInit() {
|
|
|
|
|
drivetrain = new SwerveDrive();
|
|
|
|
|
camera = new PhotonCamera(kCameraName);
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
visionSim = new VisionSim(camera);
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
controller = new XboxController(0);
|
|
|
|
|
}
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-08-31 13:44:19 -04:00
|
|
|
@Override
|
|
|
|
|
public void robotPeriodic() {
|
2024-09-14 23:10:02 -05:00
|
|
|
// Update drivetrain subsystem
|
|
|
|
|
drivetrain.periodic();
|
|
|
|
|
|
|
|
|
|
// Log values to the dashboard
|
|
|
|
|
drivetrain.log();
|
2024-08-31 13:44:19 -04:00
|
|
|
}
|
|
|
|
|
|
2021-01-16 20:41:47 -08:00
|
|
|
@Override
|
2024-09-14 23:10:02 -05:00
|
|
|
public void disabledPeriodic() {
|
|
|
|
|
drivetrain.stop();
|
|
|
|
|
}
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
@Override
|
|
|
|
|
public void teleopInit() {
|
|
|
|
|
resetPose();
|
|
|
|
|
}
|
2021-01-26 22:26:15 -06:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
@Override
|
|
|
|
|
public void teleopPeriodic() {
|
|
|
|
|
// Calculate drivetrain commands from Joystick values
|
|
|
|
|
double forward = -controller.getLeftY() * Constants.Swerve.kMaxLinearSpeed;
|
|
|
|
|
double strafe = -controller.getLeftX() * Constants.Swerve.kMaxLinearSpeed;
|
|
|
|
|
double turn = -controller.getRightX() * Constants.Swerve.kMaxAngularSpeed;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
// Read in relevant data from the Camera
|
|
|
|
|
boolean targetVisible = false;
|
|
|
|
|
double targetYaw = 0.0;
|
|
|
|
|
var results = camera.getAllUnreadResults();
|
|
|
|
|
if (!results.isEmpty()) {
|
|
|
|
|
// Camera processed a new frame since last
|
|
|
|
|
// Get the last one in the list.
|
|
|
|
|
var result = results.get(results.size() - 1);
|
2021-01-16 20:41:47 -08:00
|
|
|
if (result.hasTargets()) {
|
2024-09-14 23:10:02 -05:00
|
|
|
// At least one AprilTag was seen by the camera
|
|
|
|
|
for (var target : result.getTargets()) {
|
|
|
|
|
if (target.getFiducialId() == 7) {
|
|
|
|
|
// Found Tag 7, record its information
|
|
|
|
|
targetYaw = target.getYaw();
|
|
|
|
|
targetVisible = true;
|
|
|
|
|
}
|
|
|
|
|
}
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2024-09-14 23:10:02 -05:00
|
|
|
// Auto-align when requested
|
|
|
|
|
if (controller.getAButton() && targetVisible) {
|
|
|
|
|
// Driver wants auto-alignment to tag 7
|
|
|
|
|
// And, tag 7 is in sight, so we can turn toward it.
|
|
|
|
|
// Override the driver's turn command with an automatic one that turns toward the tag.
|
|
|
|
|
turn = -1.0 * targetYaw * VISION_TURN_kP * Constants.Swerve.kMaxAngularSpeed;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
// Command drivetrain motors based on target speeds
|
|
|
|
|
drivetrain.drive(forward, strafe, turn);
|
|
|
|
|
|
|
|
|
|
// Put debug information to the dashboard
|
|
|
|
|
SmartDashboard.putBoolean("Vision Target Visible", targetVisible);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Override
|
|
|
|
|
public void simulationPeriodic() {
|
|
|
|
|
// Update drivetrain simulation
|
|
|
|
|
drivetrain.simulationPeriodic();
|
|
|
|
|
|
|
|
|
|
// Update camera simulation
|
|
|
|
|
visionSim.simulationPeriodic(drivetrain.getSimPose());
|
|
|
|
|
|
|
|
|
|
var debugField = visionSim.getSimDebugField();
|
|
|
|
|
debugField.getObject("EstimatedRobot").setPose(drivetrain.getPose());
|
|
|
|
|
debugField.getObject("EstimatedRobotModules").setPoses(drivetrain.getModulePoses());
|
|
|
|
|
|
|
|
|
|
// Calculate battery voltage sag due to current draw
|
2024-11-21 19:21:27 -05:00
|
|
|
var batteryVoltage =
|
|
|
|
|
BatterySim.calculateDefaultBatteryLoadedVoltage(drivetrain.getCurrentDraw());
|
|
|
|
|
|
|
|
|
|
// Using max(0.1, voltage) here isn't a *physically correct* solution,
|
|
|
|
|
// but it avoids problems with battery voltage measuring 0.
|
|
|
|
|
RoboRioSim.setVInVoltage(Math.max(0.1, batteryVoltage));
|
2024-09-14 23:10:02 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void resetPose() {
|
|
|
|
|
// Example Only - startPose should be derived from some assumption
|
|
|
|
|
// of where your robot was placed on the field.
|
|
|
|
|
// The first pose in an autonomous path is often a good choice.
|
|
|
|
|
var startPose = new Pose2d(1, 1, new Rotation2d());
|
|
|
|
|
drivetrain.resetPose(startPose, true);
|
|
|
|
|
visionSim.resetSimPose(startPose);
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
}
|