Skip to content

Commit f87244f

Browse files
committed
Small edits, fully functioning arm subsystem
1 parent cb4092a commit f87244f

File tree

4 files changed

+12
-9
lines changed

4 files changed

+12
-9
lines changed

src/main/java/frc/robot/Constants.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ public static class ArmConstants {
172172
public static final double LIFT_HEIGHT_2 = 2;
173173
public static final double LIFT_HEIGHT_3 = 3;
174174

175-
public static final double LIFT_SPEED = 0.05;
175+
public static final double LIFT_SPEED = 0.1;
176176
public static final double CORAL_INTAKE_SPEED = 0.03;
177177
}
178178

src/main/java/frc/robot/RobotContainer.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,6 @@ private void configureBindings() {
8383
*/
8484
public Command getAutonomousCommand() {
8585
// An example command will be run in autonomous
86-
return Autos.driveStraight(m_driveSubsystem, 3);
86+
return Autos.driveStraight(m_driveSubsystem, m_armSubsystem);
8787
}
8888
}

src/main/java/frc/robot/commands/Autos.java

+8-4
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,8 @@
44

55
package frc.robot.commands;
66

7+
import frc.robot.Constants;
8+
import frc.robot.subsystems.ArmSubsystem;
79
import frc.robot.subsystems.DriveSubsystem;
810
import frc.robot.subsystems.ExampleSubsystem;
911
import edu.wpi.first.wpilibj2.command.Command;
@@ -18,15 +20,17 @@ public static Command exampleAuto(ExampleSubsystem subsystem) {
1820
}
1921

2022
/** Drives for a certain number of seconds. */
21-
public static Command driveStraight(DriveSubsystem drive, double seconds) {
23+
public static Command driveStraight(DriveSubsystem drive, ArmSubsystem arm) {
2224
return new InstantCommand(() -> drive.drive(0.0, 0.5, 0.0))
23-
.andThen(new WaitCommand(seconds))
24-
.andThen(() -> drive.drive(0.0, 0.0, 0.0));
25+
.andThen(new WaitCommand(1.5))
26+
.andThen(() -> drive.drive(0.0, 0.0, 0.0))
27+
.andThen(() -> arm.setArmSpeed(Constants.ArmConstants.LIFT_SPEED))
28+
.andThen(new WaitCommand(0.5))
29+
.andThen(() -> arm.setArmSpeed(0));
2530
}
2631

2732
private Autos() {
2833
throw new UnsupportedOperationException("This is a utility class!");
2934
}
3035

31-
3236
}

src/main/java/frc/robot/subsystems/ArmSubsystem.java

+2-3
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ public ArmSubsystem(InputSubsystem inputSubsystem) {
7474
liftConfig.closedLoop.feedbackSensor(FeedbackSensor.kPrimaryEncoder);
7575

7676
SparkMaxConfig followLiftConfig = new SparkMaxConfig();
77-
followLiftConfig.follow(Constants.ArmConstants.LEFT_LIFT_CAN_ID).apply(liftConfig);
77+
followLiftConfig.apply(liftConfig);
7878

7979

8080
SparkMaxConfig coralConfig = new SparkMaxConfig();
@@ -83,7 +83,6 @@ public ArmSubsystem(InputSubsystem inputSubsystem) {
8383
SparkMaxConfig followCoralConfig = new SparkMaxConfig();
8484
followCoralConfig.follow(Constants.ArmConstants.LEFT_CORAL_CAN_ID).apply(coralConfig);
8585

86-
8786
followLiftConfig.follow(Constants.ArmConstants.LEFT_LIFT_CAN_ID, true);
8887
followCoralConfig.follow(Constants.ArmConstants.LEFT_CORAL_CAN_ID, true);
8988

@@ -123,7 +122,7 @@ public void periodic() {
123122
down) and +1.0 (full speed up.) 0 stops the arm from moving.
124123
*/
125124
public void setArmSpeed(double speed) {
126-
//armSpeed = speed;
125+
armSpeed = speed;
127126
System.out.println("Moving arm at " + (speed * 100) + "%");
128127
}
129128

0 commit comments

Comments
 (0)