Skip to content

Commit f68c54b

Browse files
FIXED ARM COMMANDS AND ADDED VORTEX OUTTAKE
1 parent 20e48ae commit f68c54b

File tree

6 files changed

+32
-25
lines changed

6 files changed

+32
-25
lines changed

src/main/java/org/carlmontrobotics/RobotContainer.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -193,10 +193,12 @@ private void setBindingsManipulatorENDEFF() {
193193
//new MoveToPos(arm, GROUND_INTAKE_POS)
194194
//MoveToPos(arm, GROUND_INTAKE_POS));
195195

196-
new JoystickButton(manipulatorController, Button.kX.value).onTrue(new MoveToPos(arm, Armc.UPPER_ANGLE_LIMIT_RAD));
196+
//new JoystickButton(manipulatorController, Button.kX.value).onTrue(new MoveToPos(arm, Armc.UPPER_ANGLE_LIMIT_RAD));
197197
new JoystickButton(manipulatorController, Button.kB.value).onTrue(new ClimbArmSoftLimit(arm));
198198
new JoystickButton(manipulatorController, Button.kLeftStick.value).onTrue(new GETOUT(intakeShooter));
199-
//NEW BINDINGS(easier for manipulator)
199+
new JoystickButton(manipulatorController, Button.kRightStick.value).onTrue(new MoveToPos(arm, -0.2));
200+
//NEW BINDINGS(easier for mani
201+
200202
//Xbox left joy Y axis -> raw Intake/Outtake control
201203
//Xbox right joy Y axis -> raw Arm control
202204
//Xbox right trigger axis -> Intake pos + intake

src/main/java/org/carlmontrobotics/commands/ClimbArmSoftLimit.java

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,8 @@
44

55
import static org.carlmontrobotics.Constants.Armc.*;
66

7-
import org.carlmontrobotics.Constants.Armc.*;
87

98
import edu.wpi.first.math.util.Units;
10-
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
11-
129
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1310
import edu.wpi.first.wpilibj2.command.Command;
1411

@@ -27,18 +24,19 @@ public void initialize() {
2724
}
2825
@Override
2926
public void execute() {
30-
arm.driveArm(SmartDashboard.getNumber("climber volts", 0));
27+
arm.driveArm(-12);
28+
3129
}
3230
@Override
3331
public void end(boolean interrupted) {
3432
arm.stopArm(); //OR maintain small voltage to keep arm in place?
3533
arm.resetSoftLimit();
36-
arm.setArmTarget(arm.getArmPos());
34+
// arm.setArmTarget(arm.getArmPos());
3735
arm.setBooleanDrive(true);
3836
}
3937
@Override
4038
public boolean isFinished() {
4139
//TODO: Figure out the actual climb position
42-
return Math.abs(arm.getArmPos() - CLIMBER_DOWN_ANGLE_RAD) < Units.degreesToRadians(5);
40+
return Math.abs(arm.getArmPos() - GROUND_INTAKE_POS) < Units.degreesToRadians(5);
4341
}
4442
}

src/main/java/org/carlmontrobotics/commands/GETOUT.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ public void execute() {
2424
public void end(boolean interrupted) {
2525
timer.stop();
2626
timer.reset();
27+
intakeShooter.setCurrentLimit(20);
2728
}
2829
@Override
2930
public boolean isFinished() {

src/main/java/org/carlmontrobotics/commands/PassToOutake.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ public void initialize(){
3737
@Override
3838
public void execute() {
3939
//intake.setMaxOutake();
40-
if (intake.getOutakeRPM()>=TEST_RPM - 1000) {//SPEAKER_RPM){
40+
if (intake.getOutakeRPM()>=4200) {//SPEAKER_RPM){
4141
intake.setMaxIntake(1);
4242
timer.start();
4343
}

src/main/java/org/carlmontrobotics/subsystems/Arm.java

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -152,6 +152,9 @@ public Arm() {
152152

153153
SmartDashboard.putNumber("ramp rate (s)", 2);
154154
SmartDashboard.putNumber("soft limit pos (rad)", SOFT_LIMIT_LOCATION_IN_RADIANS);
155+
armMotorMaster.setSmartCurrentLimit(80);
156+
armMotorFollower.setSmartCurrentLimit(80);
157+
155158
}
156159
public void setBooleanDrive(boolean climb) {
157160
callDrive = climb;
@@ -160,8 +163,8 @@ public void setBooleanDrive(boolean climb) {
160163
@Override
161164
public void periodic() {
162165

163-
armMotorMaster.setSmartCurrentLimit(50);
164-
armMotorFollower.setSmartCurrentLimit(50);
166+
// armMotorMaster.setSmartCurrentLimit(50);
167+
// armMotorFollower.setSmartCurrentLimit(50);
165168
if (DriverStation.isDisabled())
166169
resetGoal();
167170

src/main/java/org/carlmontrobotics/subsystems/IntakeShooter.java

Lines changed: 17 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -41,11 +41,11 @@
4141

4242
public class IntakeShooter extends SubsystemBase {
4343
private final CANSparkMax intakeMotor = MotorControllerFactory.createSparkMax(INTAKE_PORT, MotorConfig.NEO_550);
44-
private final CANSparkMax outakeMotor = MotorControllerFactory.createSparkMax(10, MotorConfig.NEO_550);
45-
//private final CANSparkFlex outakeMotorVortex = new CANSparkFlex(10,MotorType.kBrushless);
46-
private final RelativeEncoder outakeEncoder = outakeMotor.getEncoder();
44+
// private final CANSparkMax outakeMotor = MotorControllerFactory.createSparkMax(10, MotorConfig.NEO_550);
45+
private final CANSparkFlex outakeMotorVortex = new CANSparkFlex(10,MotorType.kBrushless);
46+
private final RelativeEncoder outakeEncoder = outakeMotorVortex.getEncoder();
4747
private final RelativeEncoder intakeEncoder = intakeMotor.getEncoder();
48-
private final SparkPIDController pidControllerOutake = outakeMotor.getPIDController();
48+
private final SparkPIDController pidControllerOutake = outakeMotorVortex.getPIDController();
4949
private final SparkPIDController pidControllerIntake = intakeMotor.getPIDController();
5050
private Timer timer = new Timer();
5151
private int count = 0;
@@ -63,7 +63,7 @@ public class IntakeShooter extends SubsystemBase {
6363
public IntakeShooter() {
6464
//Figure out which ones to set inverted
6565
intakeMotor.setInverted(INTAKE_MOTOR_INVERSION);
66-
outakeMotor.setInverted(OUTAKE_MOTOR_INVERSION);
66+
outakeMotorVortex.setInverted(OUTAKE_MOTOR_INVERSION);
6767
pidControllerOutake.setP(kP[OUTTAKE]);
6868
pidControllerOutake.setI(kI[OUTTAKE]);
6969
pidControllerOutake.setD(kD[OUTTAKE]);
@@ -74,6 +74,7 @@ public IntakeShooter() {
7474
intakeEncoder.setAverageDepth(4);
7575
intakeEncoder.setMeasurementPeriod(8);
7676
SmartDashboard.putNumber("intake volts", 0);
77+
SmartDashboard.putNumber("Vortex volts", 0);
7778
// setMaxOutakeOverload(1);
7879

7980
}
@@ -90,7 +91,7 @@ private double getGamePieceDistanceIntake() {
9091
return Units.metersToInches(intakeDistanceSensor.getRange()/1000) - DS_DEPTH_INCHES;
9192
}
9293
public void motorSetOutake(int speed) {
93-
outakeMotor.set(speed);
94+
outakeMotorVortex.set(speed);
9495
}
9596
private double getGamePieceDistanceOutake() {
9697
return Units.metersToInches(OutakeDistanceSensor.getRange()/1000) - DS_DEPTH_INCHES;
@@ -133,11 +134,12 @@ public boolean outakeDetectsNote() {
133134

134135
@Override
135136
public void periodic() {
136-
outakeMotor.set(SmartDashboard.getNumber("intake volts", 0));
137-
SmartDashboard.putNumber("outtake vel", outakeMotor.getEncoder().getVelocity());
137+
//outakeMotor.set(SmartDashboard.getNumber("intake volts", 0));
138+
SmartDashboard.putNumber("outtake vel", outakeMotorVortex.getEncoder().getVelocity());
139+
138140
//count++;
139-
//double volts = SmartDashboard.getNumber("Vortex volts", 0);
140-
//outakeMotorVortex.set(volts);
141+
double volts = SmartDashboard.getNumber("Vortex volts", 0);
142+
// outakeMotorVortex.set(volts);
141143

142144
//setMaxOutake();
143145

@@ -154,16 +156,16 @@ public void setMaxIntake(int direction) {
154156

155157
}
156158
public void setMaxOutakeOverload(int direction) {
157-
outakeMotor.setSmartCurrentLimit(40);
159+
// outakeMotor.setSmartCurrentLimit(40);
158160
//outakeMotor.setSmartCurrentLimit(1*direction);
159161
}
160162
public void setMaxOutake() {
161-
outakeMotor.set(1);
163+
outakeMotorVortex.set(1);
162164
}
163165

164166
public void resetCurrentLimit() {
165167
intakeMotor.setSmartCurrentLimit(MotorConfig.NEO_550.currentLimitAmps);
166-
outakeMotor.setSmartCurrentLimit(MotorConfig.NEO.currentLimitAmps);
168+
// outakeMotorVortex.setSmartCurrentLimit(MotorConfig.NEO.currentLimitAmps);
167169
//intakeMotor.setSmartCurrentLimit(MotorConfig.NEO_550.currentLimitAmps);
168170
}
169171

@@ -184,7 +186,8 @@ public void stopOutake() {
184186
}
185187

186188
public void stopIntake() {
187-
outakeMotor.set(0);
189+
intakeMotor.set(0);
190+
outakeMotorVortex.set(0);
188191
}
189192
public double getIntakeRPM() {
190193
return intakeEncoder.getVelocity();

0 commit comments

Comments
 (0)