diff --git a/AdvantageScope RBSI Standard.json b/AdvantageScope RBSI Standard.json new file mode 100644 index 0000000..67dc05a --- /dev/null +++ b/AdvantageScope RBSI Standard.json @@ -0,0 +1,541 @@ +{ + "hubs": [ + { + "x": 71, + "y": 33, + "width": 1315, + "height": 776, + "state": { + "sidebar": { + "width": 300, + "expanded": [ + "/RealOutputs", + "/RealOutputs/LoopSpike/Drive", + "/RealOutputs/Drive/OdomThread", + "/RealOutputs/CAN/DriveTrain", + "/RealOutputs/CAN/Module0", + "/RealOutputs/LoopSpike", + "/AdvantageKit", + "/RealOutputs/Loop/Drive", + "/RealOutputs/Loop/Mech", + "/RealOutputs/Odometry/Yaw", + "/RealOutputs/Vision/Camera0", + "/RealOutputs/Vision/Camera0/TagPoses", + "/RealOutputs/Vision/Summary/TagPoses", + "/RealOutputs/Vision/Camera1/RobotPosesAccepted", + "/RealOutputs/Vision/Camera0/RobotPosesAccepted", + "/RealOutputs/Power", + "/RealOutputs/Power/Subsystems", + "/NetworkInputs/SmartDashboard", + "/RealOutputs/Loop", + "/RealOutputs/Loop/Virtual" + ] + }, + "tabs": { + "selected": 7, + "tabs": [ + { + "type": 0, + "title": "", + "controller": null, + "controllerUUID": "27w43phb8fm0oyp20p0wxms1a35yrw0i", + "renderer": "", + "controlsHeight": 0 + }, + { + "type": 2, + "title": "2D Field - Odometry", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": true, + "options": { + "bumpers": "" + } + } + ], + "field": "FRC:2026 Field", + "orientation": 0, + "size": "large" + }, + "controllerUUID": "ibthfkqod1n0vovjoxhcg2d9954wcpe4", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 2, + "title": "2D Field - Vision", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": false, + "options": { + "bumpers": "" + } + }, + { + "type": "arrow", + "logKey": "/RealOutputs/Vision/Summary/TagPoses", + "logType": "Pose3d[]", + "visible": true, + "options": { + "position": "center" + } + }, + { + "type": "ghost", + "logKey": "/RealOutputs/Vision/Camera0/RobotPosesAccepted", + "logType": "Pose3d[]", + "visible": true, + "options": { + "color": "#00ff00" + } + }, + { + "type": "ghost", + "logKey": "/RealOutputs/Vision/Camera1/RobotPosesAccepted", + "logType": "Pose3d[]", + "visible": true, + "options": { + "color": "#ffff00" + } + } + ], + "field": "FRC:2026 Field", + "orientation": 0, + "size": "large" + }, + "controllerUUID": "u9myuirzag5qydjp9nozn8qxpfqofuuq", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 9, + "title": "Swerve", + "controller": { + "sources": [ + { + "type": "states", + "logKey": "/RealOutputs/SwerveStates/Measured", + "logType": "SwerveModuleState[]", + "visible": true, + "options": { + "color": "#ff0000", + "arrangement": "0,1,2,3" + } + }, + { + "type": "states", + "logKey": "/RealOutputs/SwerveStates/SetpointsOptimized", + "logType": "SwerveModuleState[]", + "visible": true, + "options": { + "color": "#00ffff", + "arrangement": "0,1,2,3" + } + }, + { + "type": "rotation", + "logKey": "/RealOutputs/Odometry/Robot/rotation", + "logType": "Rotation2d", + "visible": true, + "options": {} + }, + { + "type": "chassisSpeeds", + "logKey": "/RealOutputs/SwerveChassisSpeeds/Measured", + "logType": "ChassisSpeeds", + "visible": true, + "options": { + "color": "#ff0000" + } + } + ], + "maxSpeed": 5, + "sizeX": 0.65, + "sizeY": 0.65, + "orientation": 1 + }, + "controllerUUID": "zo4ukgbiguacvfe9e2iui2ytosl7gutn", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Power", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/PowerDistribution/Voltage", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + } + ], + "rightSources": [ + { + "type": "stepped", + "logKey": "/PowerDistribution/TotalCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/DriveCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/SteerCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Power/Subsystems/FlywheelCurrent", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "discreteSources": [ + { + "type": "stripes", + "logKey": "/RealOutputs/Power/BrownoutImminent", + "logType": "Boolean", + "visible": true, + "options": { + "color": "#af2437" + } + } + ], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "9vyygyem9we0y5917klbu25cz9hruszx", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "CAN Health", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/CAN//Utilization", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/Utilization", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + } + ], + "rightSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/RxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/TxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN//RxErrorCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/CAN/DriveTrain/TxFullCount", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "f15s8kcvuqce63dlc7cf4yunt6c0372w", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Loop Time - Robot", + "controller": { + "leftSources": [], + "rightSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/FullCycleMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/GCTimeMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/LogPeriodicMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/LoggedRobot/UserCodeMS", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + } + ], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "yktsi99006yw1sq2h8mihr8kiy9h5xk9", + "renderer": null, + "controlsHeight": 200 + }, + { + "type": 1, + "title": "Loop Time - Subsystems", + "controller": { + "leftSources": [ + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Mech/Drive_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#2b66a2", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Mech/Flywheel_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#e5b31b", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/Accelerometer_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#af2437", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/RBSICANHealth_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#80588e", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/RBSIPowerMonitor_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#e48b32", + "size": "normal" + } + }, + { + "type": "stepped", + "logKey": "/RealOutputs/Loop/Virtual/Vision_ms", + "logType": "Number", + "visible": true, + "options": { + "color": "#c0b487", + "size": "normal" + } + } + ], + "rightSources": [], + "discreteSources": [], + "leftLockedRange": null, + "rightLockedRange": null, + "leftUnitConversion": { + "autoTarget": null, + "preset": null + }, + "rightUnitConversion": { + "autoTarget": null, + "preset": null + }, + "leftFilter": 0, + "rightFilter": 0 + }, + "controllerUUID": "no6ewy1a2lc06qvs7einn5i430wwub9n", + "renderer": null, + "controlsHeight": 195 + }, + { + "type": 3, + "title": "3D Field", + "controller": { + "sources": [ + { + "type": "robot", + "logKey": "/RealOutputs/Vision/Summary/TagPoses", + "logType": "Pose3d[]", + "visible": true, + "options": { + "model": "Crab Bot" + } + }, + { + "type": "robot", + "logKey": "/RealOutputs/Odometry/Robot", + "logType": "Pose2d", + "visible": true, + "options": { + "model": "2026 KitBot" + } + } + ], + "game": "FRC:2026 Field" + }, + "controllerUUID": "x1j1ypjwdchzmk115shjrh4ml6w4osq9", + "renderer": { + "cameraIndex": -1, + "orbitFov": 50, + "cameraPosition": [ + 1.4695761589768238e-15, + 5.999999999999999, + -12 + ], + "cameraTarget": [ + 0, + 0.5, + 0 + ] + }, + "controlsHeight": 200 + } + ] + } + } + } + ], + "satellites": [], + "version": "26.0.0" +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 7d30eae..4a27974 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -180,30 +180,30 @@ public static class RobotDevices { // Front Left public static final RobotDeviceId FL_DRIVE = - new RobotDeviceId(SwerveConstants.kFLDriveMotorId, SwerveConstants.kFLDriveCanbus, 16); + new RobotDeviceId(SwerveConstants.kFLDriveMotorId, SwerveConstants.kFLDriveCanbus, 18); public static final RobotDeviceId FL_ROTATION = - new RobotDeviceId(SwerveConstants.kFLSteerMotorId, SwerveConstants.kFLSteerCanbus, 17); + new RobotDeviceId(SwerveConstants.kFLSteerMotorId, SwerveConstants.kFLSteerCanbus, 19); public static final RobotDeviceId FL_CANCODER = new RobotDeviceId(SwerveConstants.kFLEncoderId, SwerveConstants.kFLEncoderCanbus, null); // Front Right public static final RobotDeviceId FR_DRIVE = - new RobotDeviceId(SwerveConstants.kFRDriveMotorId, SwerveConstants.kFRDriveCanbus, 13); + new RobotDeviceId(SwerveConstants.kFRDriveMotorId, SwerveConstants.kFRDriveCanbus, 17); public static final RobotDeviceId FR_ROTATION = - new RobotDeviceId(SwerveConstants.kFRSteerMotorId, SwerveConstants.kFRSteerCanbus, 12); + new RobotDeviceId(SwerveConstants.kFRSteerMotorId, SwerveConstants.kFRSteerCanbus, 16); public static final RobotDeviceId FR_CANCODER = new RobotDeviceId(SwerveConstants.kFREncoderId, SwerveConstants.kFREncoderCanbus, null); // Back Left public static final RobotDeviceId BL_DRIVE = - new RobotDeviceId(SwerveConstants.kBLDriveMotorId, SwerveConstants.kBLDriveCanbus, 2); + new RobotDeviceId(SwerveConstants.kBLDriveMotorId, SwerveConstants.kBLDriveCanbus, 1); public static final RobotDeviceId BL_ROTATION = - new RobotDeviceId(SwerveConstants.kBLSteerMotorId, SwerveConstants.kBLSteerCanbus, 3); + new RobotDeviceId(SwerveConstants.kBLSteerMotorId, SwerveConstants.kBLSteerCanbus, 0); public static final RobotDeviceId BL_CANCODER = new RobotDeviceId(SwerveConstants.kBLEncoderId, SwerveConstants.kBLEncoderCanbus, null); // Back Right public static final RobotDeviceId BR_DRIVE = - new RobotDeviceId(SwerveConstants.kBRDriveMotorId, SwerveConstants.kBRSteerCanbus, 7); + new RobotDeviceId(SwerveConstants.kBRDriveMotorId, SwerveConstants.kBRSteerCanbus, 2); public static final RobotDeviceId BR_ROTATION = - new RobotDeviceId(SwerveConstants.kBRSteerMotorId, SwerveConstants.kBRSteerCanbus, 6); + new RobotDeviceId(SwerveConstants.kBRSteerMotorId, SwerveConstants.kBRSteerCanbus, 3); public static final RobotDeviceId BR_CANCODER = new RobotDeviceId(SwerveConstants.kBREncoderId, SwerveConstants.kBREncoderCanbus, null); // Pigeon