diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 25399b41..87f4e936 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,5 +1,7 @@ # Why are we doing this? +Asana task URL: + # Whats changing? # Questions/notes for reviewers diff --git a/.github/workflows/comment-on-task.yaml b/.github/workflows/comment-on-task.yaml new file mode 100644 index 00000000..e9eba9c0 --- /dev/null +++ b/.github/workflows/comment-on-task.yaml @@ -0,0 +1,17 @@ +on: + pull_request: + types: [opened, closed, reopened, edited, converted_to_draft, ready_for_review] + +jobs: + create-comment-in-asana-task-job: + runs-on: ubuntu-latest + name: Create a comment in Asana Task + steps: + - name: Create a comment + uses: Asana/comment-on-task-github-action@v1.2 + id: createComment + with: + asana-secret: ${{ secrets.ASANA_SECRET }} + comment-text: "{{PR_NAME}} is {{PR_STATE}}: {{PR_URL}}" + - name: Get status + run: echo "Status is ${{ steps.createComment.outputs.status }}" \ No newline at end of file diff --git a/.github/workflows/create-asana-attachment.yml b/.github/workflows/create-asana-attachment.yml new file mode 100644 index 00000000..697f1347 --- /dev/null +++ b/.github/workflows/create-asana-attachment.yml @@ -0,0 +1,16 @@ +on: + pull_request: + types: [opened, reopened, edited, converted_to_draft, ready_for_review] + +jobs: + create-asana-attachment-job: + runs-on: ubuntu-latest + name: Create pull request attachments on Asana tasks + steps: + - name: Create pull request attachments + uses: Asana/create-app-attachment-github-action@latest + id: postAttachment + with: + asana-secret: ${{ secrets.ASANA_SECRET }} + - name: Log output status + run: echo "Status is ${{ steps.postAttachment.outputs.status }}" \ No newline at end of file diff --git a/SeriouslyCommonLib b/SeriouslyCommonLib index ec1a9414..5bd2bcec 160000 --- a/SeriouslyCommonLib +++ b/SeriouslyCommonLib @@ -1 +1 @@ -Subproject commit ec1a941482965d9f4ccab51a0a0ac8834d966916 +Subproject commit 5bd2bcecddf7864f0cc30196b386d03573abb808 diff --git a/src/main/java/competition/subsystems/arm/ArmSubsystem.java b/src/main/java/competition/subsystems/arm/ArmSubsystem.java index e74915c7..fd97b147 100644 --- a/src/main/java/competition/subsystems/arm/ArmSubsystem.java +++ b/src/main/java/competition/subsystems/arm/ArmSubsystem.java @@ -20,6 +20,7 @@ public class ArmSubsystem extends BaseSubsystem { public DoubleProperty extendPower; public DoubleProperty retractPower; + private DoubleProperty setPowerMax; private DoubleProperty setPowerMin; @@ -37,7 +38,7 @@ public ArmSubsystem(PropertyFactory pf, XCANSparkMax.XCANSparkMaxFactory sparkMa extendPower = pf.createPersistentProperty("ExtendPower", 0.1); retractPower = pf.createPersistentProperty("RetractPower", 0.1); - + setPowerMax = pf.createPersistentProperty("SetPowerMax", 0.5); setPowerMin = pf.createPersistentProperty("SetPowerMin", -0.5); diff --git a/src/main/java/competition/subsystems/collector/commands/IntakeUntilNoteCollectedCommand.java b/src/main/java/competition/subsystems/collector/commands/IntakeUntilNoteCollectedCommand.java index bf93f83a..a28e02ae 100644 --- a/src/main/java/competition/subsystems/collector/commands/IntakeUntilNoteCollectedCommand.java +++ b/src/main/java/competition/subsystems/collector/commands/IntakeUntilNoteCollectedCommand.java @@ -10,6 +10,7 @@ public class IntakeUntilNoteCollectedCommand extends BaseCommand { @Inject public IntakeUntilNoteCollectedCommand(CollectorSubsystem collector) { this.collector = collector; + addRequirements(collector); } @Override public void initialize() { diff --git a/src/main/java/competition/subsystems/drive/commands/TankDriveWithJoysticksCommand.java b/src/main/java/competition/subsystems/drive/commands/TankDriveWithJoysticksCommand.java index cae20480..4bfcf466 100644 --- a/src/main/java/competition/subsystems/drive/commands/TankDriveWithJoysticksCommand.java +++ b/src/main/java/competition/subsystems/drive/commands/TankDriveWithJoysticksCommand.java @@ -16,7 +16,7 @@ public class TankDriveWithJoysticksCommand extends BaseCommand { public TankDriveWithJoysticksCommand(OperatorInterface oi, DriveSubsystem driveSubsystem) { this.oi = oi; this.driveSubsystem = driveSubsystem; - this.addRequirements(this.driveSubsystem); + this.addRequirements(driveSubsystem); } @Override diff --git a/src/main/java/competition/subsystems/vision/VisionSubsystem.java b/src/main/java/competition/subsystems/vision/VisionSubsystem.java index f6bd980a..9bf67ba7 100644 --- a/src/main/java/competition/subsystems/vision/VisionSubsystem.java +++ b/src/main/java/competition/subsystems/vision/VisionSubsystem.java @@ -39,7 +39,7 @@ public class VisionSubsystem extends BaseSubsystem implements DataFrameRefreshab public static final String TARGET_POSE = "forwardAprilCamera/targetPose"; public static final String LATENCY_MILLIS = "forwardAprilCamera/latencyMillis"; - //final PhotonCamera forwardAprilCamera; + final PhotonCameraExtended forwardAprilCamera; final PhotonCameraExtended rearAprilCamera; //final XPhotonCamera akitForwardAprilCamera; @@ -62,11 +62,6 @@ public class VisionSubsystem extends BaseSubsystem implements DataFrameRefreshab @Inject public VisionSubsystem(PropertyFactory pf, RobotAssertionManager assertionManager) { - - // Temporary while waiting for PhotonVision to update and make this plausible - // akitForwardAprilCamera = cameraFactory.create("forwardAprilCamera"); - //akitRearAprilCamera = cameraFactory.create("rearAprilCamera"); - this.assertionManager = assertionManager; visionTable = NetworkTableInstance.getDefault().getTable(VISION_TABLE); @@ -83,7 +78,7 @@ public VisionSubsystem(PropertyFactory pf, RobotAssertionManager assertionManage // of errors. Some sort of VisionReady in the ElectricalContract may also make sense. Similarly, // we need to handle cases like not having the AprilTag data loaded. - //forwardAprilCamera = new PhotonCamera("forwardAprilCamera"); + forwardAprilCamera = new PhotonCameraExtended("forwardAprilCamera"); rearAprilCamera = new PhotonCameraExtended("rearAprilCamera"); try { @@ -106,12 +101,12 @@ public VisionSubsystem(PropertyFactory pf, RobotAssertionManager assertionManage 16.421 / PoseSubsystem.INCHES_IN_A_METER), new Rotation3d(0, 0, Math.toRadians(180 + 7.595))); - /*frontPhotonPoseEstimator = new PhotonPoseEstimator( + frontPhotonPoseEstimator = new PhotonPoseEstimator( aprilTagFieldLayout, PhotonPoseEstimator.PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, forwardAprilCamera, robotToCam - );*/ + ); rearPhotonPoseEstimator = new PhotonPoseEstimator( aprilTagFieldLayout, PhotonPoseEstimator.PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, @@ -122,9 +117,9 @@ public VisionSubsystem(PropertyFactory pf, RobotAssertionManager assertionManage public Optional[] getPhotonVisionEstimatedPoses(Pose2d previousEstimatedRobotPose) { if (visionWorking) { - //var frontEstimatedPose = getPhotonVisionEstimatedPose("Front", frontPhotonPoseEstimator, previousEstimatedRobotPose, frontReliablePoseIsStable); + var frontEstimatedPose = getPhotonVisionEstimatedPose("Front", frontPhotonPoseEstimator, previousEstimatedRobotPose, frontReliablePoseIsStable); var rearEstimatedPose = getPhotonVisionEstimatedPose("Rear", rearPhotonPoseEstimator, previousEstimatedRobotPose, rearReliablePoseIsStable); - return new Optional[] {/*frontEstimatedPose,*/ rearEstimatedPose}; + return new Optional[] {frontEstimatedPose, rearEstimatedPose}; } else { return new Optional[] {Optional.empty()}; } @@ -136,9 +131,10 @@ public Optional getPhotonVisionEstimatedPose( estimator.setReferencePose(previousEstimatedRobotPose); var estimatedPose = estimator.update(); // Log the estimated pose, and log an insane value if we don't have one (so we don't clutter up the visualization) - Logger.recordOutput(getPrefix()+name+"Estimate", estimatedPose.isPresent() - ? estimatedPose.get().estimatedPose.toPose2d() : - new Pose2d(-1000, -1000, new Rotation2d(0))); + if (estimatedPose.isPresent()) + { + Logger.recordOutput(getPrefix()+name+"Estimate", estimatedPose.get().estimatedPose.toPose2d()); + } var isReliable = !estimatedPose.isEmpty() && isEstimatedPoseReliable(estimatedPose.get(), previousEstimatedRobotPose); var isStable = waitForStablePoseTime.get() == 0.0 || poseTimeValidator.checkStable(isReliable); @@ -211,6 +207,7 @@ private String getStringFromList(List list) { @Override public void refreshDataFrame() { + forwardAprilCamera.refreshDataFrame(); rearAprilCamera.refreshDataFrame(); } }