Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@

{
"java.configuration.updateBuildConfiguration": "interactive",
"java.configuration.updateBuildConfiguration": "disabled",
"java.server.launchMode": "Standard",
"files.exclude": {
"**/.git": true,
Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ import edu.wpi.first.gradlerio.deploy.roborio.RoboRIO

plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2022.3.1"
id "edu.wpi.first.GradleRIO" version "2022.4.1"
id "jacoco"
}

Expand Down
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,14 @@ public class Robot extends TimedRobot {
DriveModule rightModule;
LoggableController driver;
LoggableController operator;
Shooter shooter;

LoggablePowerDistribution pdp;
LoggableCompressor compressor;

boolean drivetrainEnabled = true;
boolean tankDriveEnabled = true;
boolean shooterEnabled = true;

private static final double DEADBAND_LIMIT = 0.01;
private static final double SPEED_CAP = 0.6;
Expand Down Expand Up @@ -78,6 +80,13 @@ public void robotInit() {
} else {
System.out.println("Drivetrain initialization disabled.");
}
if (this.shooterEnabled) {
System.out.println("Initializing shooter...");
shooter = new Shooter(6);
logger.addLoggable(shooter);
} else {
System.out.println("Shooter initialization disabled.");
}

System.out.print("Initializing compressor...");
compressor = new LoggableCompressor(PneumaticsModuleType.REVPH);
Expand Down Expand Up @@ -134,6 +143,9 @@ public void teleopPeriodic() {
leftModule.updateCurrent();
rightModule.updateCurrent();
}
if (this.shooterEnabled) {
shooter.setSpeed(driver.getRightTriggerAxis());
}

logger.log();
logger.writeLine();
Expand Down
38 changes: 38 additions & 0 deletions src/main/java/frc/robot/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
package frc.robot;

import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.TalonFX;
import frc.robot.logging.Loggable;

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Extra separation in import group before 'frc.robot.logging.Loggable'

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Import statement for 'frc.robot.logging.Loggable' is in the wrong order. Should be in the 'THIRD_PARTY_PACKAGE' group, expecting not assigned imports on this line.

import frc.robot.logging.Logger;

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Import statement for 'frc.robot.logging.Logger' is in the wrong order. Should be in the 'THIRD_PARTY_PACKAGE' group, expecting not assigned imports on this line.


public class Shooter implements Loggable {
TalonFX shooterMotor;
public Shooter(int shooterID) {

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

'CTOR_DEF' should be separated from previous statement.

this.shooterMotor = new TalonFX(shooterID);

this.shooterMotor.setNeutralMode(NeutralMode.Coast);
}

public void setSpeed(double speed) {
shooterMotor.set(ControlMode.Velocity, speed);
}

public void setPower(double power) {
shooterMotor.set(ControlMode.PercentOutput, power);
}

public double getSpeed() {
return shooterMotor.getSelectedSensorVelocity();
}

@Override
public void setupLogging(Logger logger) {
logger.addAttribute("Shooter/speed");
}

@Override
public void log(Logger logger) {
logger.log("Shooter/speed", this.getSpeed());
}
}