removed algae beam break
This commit is contained in:
parent
89c1914d11
commit
6fa4377e52
@ -192,10 +192,12 @@ public class RobotContainer {
|
|||||||
.withPosition(4, 1)
|
.withPosition(4, 1)
|
||||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||||
|
|
||||||
|
/*
|
||||||
sensorTab.addBoolean("Algae Sensor", manipulator::getAlgaePhotoSwitch)
|
sensorTab.addBoolean("Algae Sensor", manipulator::getAlgaePhotoSwitch)
|
||||||
.withSize(1, 1)
|
.withSize(1, 1)
|
||||||
.withPosition(4, 0)
|
.withPosition(4, 0)
|
||||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
public Command getAutonomousCommand() {
|
public Command getAutonomousCommand() {
|
||||||
@ -211,8 +213,8 @@ public class RobotContainer {
|
|||||||
ElevatorConstants.kCoralIntakePosition,
|
ElevatorConstants.kCoralIntakePosition,
|
||||||
ManipulatorPivotConstants.kCoralIntakePosition
|
ManipulatorPivotConstants.kCoralIntakePosition
|
||||||
)
|
)
|
||||||
.andThen(manipulator.runUntilCollected(1, true));
|
.andThen(manipulator.runUntilCollected(1));
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Moves the elevator and arm to the constant setpoints and runs the manipulator until collected
|
* Moves the elevator and arm to the constant setpoints and runs the manipulator until collected
|
||||||
@ -225,7 +227,7 @@ public class RobotContainer {
|
|||||||
l2 ? ElevatorConstants.kL2AlgaePosition : ElevatorConstants.kL3AlgaePosition,
|
l2 ? ElevatorConstants.kL2AlgaePosition : ElevatorConstants.kL3AlgaePosition,
|
||||||
l2 ? ManipulatorPivotConstants.kL2AlgaePosition : ManipulatorPivotConstants.kL3AlgaePosition
|
l2 ? ManipulatorPivotConstants.kL2AlgaePosition : ManipulatorPivotConstants.kL3AlgaePosition
|
||||||
)
|
)
|
||||||
.andThen(manipulator.runUntilCollected(1, false));
|
.andThen(manipulator.runUntilCollected(1));
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -17,7 +17,8 @@ public class ElevatorConstants {
|
|||||||
public static final int kTopLimitSwitchID = 0;
|
public static final int kTopLimitSwitchID = 0;
|
||||||
public static final int kBottomLimitSwitchID = 0;
|
public static final int kBottomLimitSwitchID = 0;
|
||||||
|
|
||||||
public static final double kEncoderConversionFactor = 0;
|
// 60/12 gearing multiplied by circumference of sprocket multiplied by 2 for carriage position
|
||||||
|
public static final double kEncoderConversionFactor = 11/60 * Math.PI * 1.75 * 2;
|
||||||
|
|
||||||
public static final int kMotorAmpsMax = 40;
|
public static final int kMotorAmpsMax = 40;
|
||||||
|
|
||||||
|
@ -19,6 +19,8 @@ public class ManipulatorPivotConstants {
|
|||||||
|
|
||||||
public static final int kMotorAmpsMax = 40;
|
public static final int kMotorAmpsMax = 40;
|
||||||
|
|
||||||
|
public static final double kPivotConversion = 12/60 * 20/60 * 28/12;
|
||||||
|
|
||||||
public static final double kPivotMaxVelocity = 0;
|
public static final double kPivotMaxVelocity = 0;
|
||||||
|
|
||||||
public static final double kPositionalP = 0;
|
public static final double kPositionalP = 0;
|
||||||
@ -81,6 +83,7 @@ public class ManipulatorPivotConstants {
|
|||||||
motorConfig
|
motorConfig
|
||||||
.smartCurrentLimit(kMotorAmpsMax)
|
.smartCurrentLimit(kMotorAmpsMax)
|
||||||
.idleMode(kIdleMode);
|
.idleMode(kIdleMode);
|
||||||
|
motorConfig.encoder.positionConversionFactor(kPivotConversion);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -16,7 +16,7 @@ public class Manipulator extends SubsystemBase {
|
|||||||
private SparkMax manipulatorMotor;
|
private SparkMax manipulatorMotor;
|
||||||
|
|
||||||
private DigitalInput coralBeamBreak;
|
private DigitalInput coralBeamBreak;
|
||||||
private DigitalInput algaeBeamBreak;
|
// private DigitalInput algaeBeamBreak;
|
||||||
|
|
||||||
public Manipulator() {
|
public Manipulator() {
|
||||||
manipulatorMotor = new SparkMax(
|
manipulatorMotor = new SparkMax(
|
||||||
@ -31,7 +31,7 @@ public class Manipulator extends SubsystemBase {
|
|||||||
);
|
);
|
||||||
|
|
||||||
coralBeamBreak = new DigitalInput(ManipulatorConstants.kCoralBeamBreakID);
|
coralBeamBreak = new DigitalInput(ManipulatorConstants.kCoralBeamBreakID);
|
||||||
algaeBeamBreak = new DigitalInput(ManipulatorConstants.kAlgaeBeamBreakID);
|
// algaeBeamBreak = new DigitalInput(ManipulatorConstants.kAlgaeBeamBreakID);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -42,10 +42,8 @@ public class Manipulator extends SubsystemBase {
|
|||||||
*/
|
*/
|
||||||
public Command defaultCommand() {
|
public Command defaultCommand() {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
manipulatorMotor.set(
|
runUntilCollected(0.1);
|
||||||
algaeBeamBreak.get() ? 0.1 : 0
|
});
|
||||||
);
|
|
||||||
});
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -70,19 +68,15 @@ public class Manipulator extends SubsystemBase {
|
|||||||
* @param coral Is the object a coral? (True = Coral, False = Algae)
|
* @param coral Is the object a coral? (True = Coral, False = Algae)
|
||||||
* @return Returns a command that sets the speed of the motor
|
* @return Returns a command that sets the speed of the motor
|
||||||
*/
|
*/
|
||||||
public Command runUntilCollected(double speed, boolean coral) {
|
public Command runUntilCollected(double speed) {
|
||||||
return run(() -> {
|
return run(() -> {
|
||||||
manipulatorMotor.set(
|
manipulatorMotor.set(
|
||||||
coral ? speed : speed * -1
|
speed * -1
|
||||||
);
|
);
|
||||||
}).until(() -> coralBeamBreak.get() || algaeBeamBreak.get());
|
}).until(() -> coralBeamBreak.get());
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean getCoralBeamBreak() {
|
public boolean getCoralBeamBreak() {
|
||||||
return coralBeamBreak.get();
|
return coralBeamBreak.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean getAlgaePhotoSwitch() {
|
|
||||||
return algaeBeamBreak.get();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user