Skip to content

Commit

Permalink
Added a lot more buttons for 3 dif speaker, and climber
Browse files Browse the repository at this point in the history
  • Loading branch information
Kenneth-Choothakan committed Mar 1, 2024
1 parent 1957d0c commit 0686ec9
Show file tree
Hide file tree
Showing 8 changed files with 235 additions and 11 deletions.
16 changes: 13 additions & 3 deletions src/main/java/org/carlmontrobotics/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,13 @@ public static final class Arm {
// USE RADIANS FOR THE ARM
public static final double intakeAngle = Math.toRadians(0);
public static final double ampAngle = Math.toRadians(103);
public static final double speakerAngle = Math.toRadians(24);
public static final double placeholderSpeakerAngle1 = Math.toRadians(24);
public static final double placeholderSpeakerAngle2 = Math.toRadians(24);
public static final double placeholderSpeakerAngle3 = Math.toRadians(24);
public static final double climberUpAngle = Math.toRadians(24);
public static final double climberDownAngle = Math.toRadians(24);


//if needed
public static final double UPPER_ANGLE_LIMIT = Math.toRadians(70);
public static final double LOWER_ANGLE_LIMIT = Math.toRadians(0);
Expand Down Expand Up @@ -61,9 +67,13 @@ public static final class Arm {
public static TrapezoidProfile.Constraints trapConstraints = new TrapezoidProfile.Constraints(MAX_FF_VEL, MAX_FF_ACCEL);

//Arm buttons
public static final int raiseToSpeakerButton = Button.kY.value;
public static final int raiseToSpeakerPodButton = Button.kY.value;
public static final int raiseToAmpButton = Button.kB.value;
public static final int raiseToGroundButton = Button.kA.value;
public static final int raiseToSpeakerSafeButton = Button.kA.value;
public static final int raiseToSpeakerNextButton = Button.kX.value;
public static final int raiseToGroundButton = Button.kStart.value;
public static final int raiseToClimberButton = Button.kLeftBumper.value;
public static final int lowerToClimberButton = Button.kRightBumper.value;
}
public static final class IntakeShooter {
//in set() speed
Expand Down
12 changes: 10 additions & 2 deletions src/main/java/org/carlmontrobotics/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import org.carlmontrobotics.commands.ArmTeleop;
import org.carlmontrobotics.commands.armAmpPos;
import org.carlmontrobotics.commands.armGroundPos;
import org.carlmontrobotics.commands.armSpeakerPos;
import org.carlmontrobotics.commands.armPodiumSpeakerPos;
import org.carlmontrobotics.subsystems.Arm;

import edu.wpi.first.wpilibj.GenericHID;
Expand Down Expand Up @@ -71,9 +71,17 @@ private void setBindingsManipulator() {
//3 setpositions of arm on letterpad
//Up is Speaker, down is ground, right is Amp
//right joystick used for manual arm control
new JoystickButton(manipulatorController, Constants.Arm.raiseToSpeakerButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armSpeakerPos(arm);}));

// Speaker Buttons
new JoystickButton(manipulatorController, Constants.Arm.raiseToSpeakerPodButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armPodiumSpeakerPos(arm);}));
new JoystickButton(manipulatorController, Constants.Arm.raiseToSpeakerNextButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armNextToSpeakerPos(arm);}));
new JoystickButton(manipulatorController, Constants.Arm.raiseToSpeakerSafeButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armSafeZonePos(arm);}));
// Amp and Intake Buttons
new JoystickButton(manipulatorController, Constants.Arm.raiseToAmpButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armAmpPos(arm);}));
new JoystickButton(manipulatorController, Constants.Arm.raiseToGroundButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armGroundPos(arm);}));
// Cimber Buttons
new JoystickButton(manipulatorController, Constants.Arm.raiseToClimberButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armClimberUpPos(arm);}));
new JoystickButton(manipulatorController, Constants.Arm.lowerToClimberButton).onTrue(new InstantCommand(() -> {arm.cancelArmCommand(); new armClimberDownPos(arm);}));
}

public Command getAutonomousCommand() {
Expand Down
47 changes: 47 additions & 0 deletions src/main/java/org/carlmontrobotics/commands/armClimberDownPos.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package org.carlmontrobotics.commands;
import org.carlmontrobotics.subsystems.Arm;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class armClimberDownPos extends Command {
/** Creates a new armPosAmp. */
private Arm arm;
private Timer armProfileTimer = new Timer();
public armClimberDownPos(Arm arm) {
// Use addRequirements() here to declare subsystem dependencies.
this.arm = arm;
addRequirements(arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
armProfileTimer.reset();
armProfileTimer.start();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
TrapezoidProfile.State setpoint = arm.calculateSetPoint(armProfileTimer.get(), arm.getCurrentArmState(), 6);
arm.COMBINE_PID_FF_TRAPEZOID(setpoint);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
armProfileTimer.stop();
armProfileTimer.reset();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
47 changes: 47 additions & 0 deletions src/main/java/org/carlmontrobotics/commands/armClimberUpPos.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package org.carlmontrobotics.commands;
import org.carlmontrobotics.subsystems.Arm;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class armClimberUpPos extends Command {
/** Creates a new armPosAmp. */
private Arm arm;
private Timer armProfileTimer = new Timer();
public armClimberUpPos(Arm arm) {
// Use addRequirements() here to declare subsystem dependencies.
this.arm = arm;
addRequirements(arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
armProfileTimer.reset();
armProfileTimer.start();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
TrapezoidProfile.State setpoint = arm.calculateSetPoint(armProfileTimer.get(), arm.getCurrentArmState(), 5);
arm.COMBINE_PID_FF_TRAPEZOID(setpoint);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
armProfileTimer.stop();
armProfileTimer.reset();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package org.carlmontrobotics.commands;
import org.carlmontrobotics.subsystems.Arm;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class armNextToSpeakerPos extends Command {
/** Creates a new armPosAmp. */
private Arm arm;
private Timer armProfileTimer = new Timer();
public armNextToSpeakerPos(Arm arm) {
// Use addRequirements() here to declare subsystem dependencies.
this.arm = arm;
addRequirements(arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
armProfileTimer.reset();
armProfileTimer.start();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
TrapezoidProfile.State setpoint = arm.calculateSetPoint(armProfileTimer.get(), arm.getCurrentArmState(), 3);
arm.COMBINE_PID_FF_TRAPEZOID(setpoint);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
armProfileTimer.stop();
armProfileTimer.reset();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class armSpeakerPos extends Command {
public class armPodiumSpeakerPos extends Command {
/** Creates a new armPosAmp. */
private Arm arm;
private Timer armProfileTimer = new Timer();
public armSpeakerPos(Arm arm) {
public armPodiumSpeakerPos(Arm arm) {
// Use addRequirements() here to declare subsystem dependencies.
this.arm = arm;
addRequirements(arm);
Expand Down
48 changes: 48 additions & 0 deletions src/main/java/org/carlmontrobotics/commands/armSafeZonePos.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package org.carlmontrobotics.commands;
import org.carlmontrobotics.subsystems.Arm;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;

public class armSafeZonePos extends Command {
/** Creates a new armPosAmp. */
private Arm arm;
private Timer armProfileTimer = new Timer();
public armSafeZonePos(Arm arm) {
// Use addRequirements() here to declare subsystem dependencies.
this.arm = arm;
addRequirements(arm);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
armProfileTimer.reset();
armProfileTimer.start();
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
TrapezoidProfile.State setpoint = arm.calculateSetPoint(armProfileTimer.get(), arm.getCurrentArmState(), 4);
arm.COMBINE_PID_FF_TRAPEZOID(setpoint);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
armProfileTimer.stop();
armProfileTimer.reset();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

24 changes: 20 additions & 4 deletions src/main/java/org/carlmontrobotics/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
import edu.wpi.first.math.trajectory.TrapezoidProfile;



public class Arm extends SubsystemBase {
private final CANSparkMax armMotor1 = MotorControllerFactory.createSparkMax(LEFT_MOTOR_PORT,MotorConfig.NEO);
//private final CANSparkMax armMotor2 = MotorControllerFactory.createSparkMax(Constants.Arm.RIGHT_MOTOR_PORT,MotorConfig.NEO);
Expand All @@ -54,7 +55,11 @@ public class Arm extends SubsystemBase {
public static TrapezoidProfile.State[] goalState = {
new TrapezoidProfile.State(Constants.Arm.intakeAngle, 0),
new TrapezoidProfile.State(Constants.Arm.ampAngle, 0),
new TrapezoidProfile.State(Constants.Arm.speakerAngle, 0),
new TrapezoidProfile.State(Constants.Arm.placeholderSpeakerAngle1, 0),
new TrapezoidProfile.State(Constants.Arm.placeholderSpeakerAngle2, 0),
new TrapezoidProfile.State(Constants.Arm.placeholderSpeakerAngle3, 0),
new TrapezoidProfile.State(Constants.Arm.climberUpAngle, 0),
new TrapezoidProfile.State(Constants.Arm.climberDownAngle, 0),
};

TrapezoidProfile profile = new TrapezoidProfile(Constants.Arm.trapConstraints);
Expand Down Expand Up @@ -102,9 +107,8 @@ public TrapezoidProfile.State calculateCustomSetPoint(double goalSeconds, Trapez

public void COMBINE_PID_FF_TRAPEZOID(TrapezoidProfile.State setPoint) {
// feed forward still needs the math part
double setClampedPointPosition = getArmClampedGoal(setPoint.position);
double armFeedVolts = armFeed.calculate(setPoint.velocity, 0);
armPID.setReference(setClampedPointPosition, CANSparkMax.ControlType.kPosition,0, armFeedVolts);
armPID.setReference(setPoint.position, CANSparkMax.ControlType.kPosition,0, armFeedVolts);
}

public double getArmPos() {
Expand All @@ -131,7 +135,7 @@ public double getArmVel() {

public double getArmClampedGoal(double goal) {
//Find the limits of the arm. Used to move it and ensure that the arm does not move past the amount
return MathUtil.clamp(goal, Constants.Arm.LOWER_ANGLE_LIMIT, Constants.Arm.UPPER_ANGLE_LIMIT);
return MathUtil.clamp(MathUtil.inputModulus(goal, Constants.Arm.ARM_DISCONT_RAD, Constants.Arm.ARM_DISCONT_RAD + 2 * Math.PI), Constants.Arm.LOWER_ANGLE_LIMIT, Constants.Arm.UPPER_ANGLE_LIMIT);
}

public TrapezoidProfile.State getCurrentArmState() {
Expand All @@ -157,9 +161,21 @@ public void periodic() {

autoCancelArmCommand();



// kP = SmartDashboard.getNumber("kP", kP);
// kD = SmartDashboard.getNumber("kD", kD);
// kI = SmartDashboard.getNumber("kI", kI);

if (armPID.getP() != kP) {
armPID.setP(kP);
}
if (armPID.getD() != kD) {
armPID.setD(kD);
}
if (armPID.getI() != kI) {
armPID.setI(kI);
}

}
}

0 comments on commit 0686ec9

Please sign in to comment.