Skip to content

Commit

Permalink
fixed null exception
Browse files Browse the repository at this point in the history
  • Loading branch information
ProfessorAtomicManiac committed Mar 10, 2024
1 parent 892ec7c commit 813432d
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ java {
targetCompatibility = JavaVersion.VERSION_17
}

def ROBOT_MAIN_CLASS = "frc.robot.Main"
def ROBOT_MAIN_CLASS = "org.carlmontrobotics.Main"

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/org/carlmontrobotics/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ public class Arm extends SubsystemBase {
private final SparkPIDController armPIDMaster = armMotorMaster.getPIDController();
private static TrapezoidProfile.State setpoint;

private TrapezoidProfile armProfile = new TrapezoidProfile(TRAP_CONSTRAINTS);
private TrapezoidProfile armProfile;
TrapezoidProfile.State goalState = new TrapezoidProfile.State(0, 0);// TODO: update pos later

// rad, rad/s
Expand Down Expand Up @@ -112,6 +112,7 @@ public Arm() {
armFeed.maxAchievableVelocity(12, Math.PI/2, 0),
MAX_FF_ACCEL_RAD_P_S);
//^ worst case scenario
armProfile = new TrapezoidProfile(TRAP_CONSTRAINTS);

SmartDashboard.putData("Arm", this);

Expand All @@ -137,6 +138,8 @@ public void periodic() {
// ARM_TELEOP_MAX_GOAL_DIFF_FROM_CURRENT_RAD);
// armConstraints = new TrapezoidProfile.Constraints(MAX_FF_VEL , MAX_FF_ACCEL
// );
SmartDashboard.putNumber("Current Position", armMasterEncoder.getPosition());


// smart dahsboard stuff
// SmartDashboard.putBoolean("ArmPIDAtSetpoint", armPID1.atSetpoint());
Expand Down

0 comments on commit 813432d

Please sign in to comment.