testing stuff day one

This commit is contained in:
Team 2648 2025-02-11 19:10:01 -05:00
parent f0b7955faa
commit 187e7385c8
7 changed files with 57 additions and 19 deletions

View File

@ -0,0 +1,13 @@
{
"NetworkTables Settings": {
"mode": "Client (NT4)"
},
"transitory": {
"Shuffleboard": {
"Sensors Tab": {
"open": true
},
"open": true
}
}
}

View File

@ -93,7 +93,8 @@ public class RobotContainer {
//elevator.runAssistedElevator(operator::getLeftY)
// );
elevator.setDefaultCommand(moveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kCoralIntakePosition));
//elevator.setDefaultCommand(moveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kCoralIntakePosition));
elevator.setDefaultCommand(elevator.manualControl(() -> 0.0));
manipulatorPivot.setDefaultCommand(moveManipulator(ElevatorConstants.kCoralIntakePosition, ManipulatorPivotConstants.kCoralIntakePosition));
@ -114,10 +115,27 @@ public class RobotContainer {
manipulator.runManipulator(() -> 1, true)
);
driver.leftTrigger().whileTrue(
manipulator.runUntilCollected(() -> 0.75)
);
driver.start().and(driver.back()).onTrue(
startingConfig()
);
driver.povDown().whileTrue(climberPivot.runPivot(-0.5));
driver.povUp().whileTrue(climberPivot.runPivot(0.5));
driver.povLeft().whileTrue(climberRollers.runRoller(0.5));
driver.povRight().whileTrue(climberRollers.runRoller(-0.5));
operator.povUp().whileTrue(elevator.goToSetpoint(30.0));
operator.a().whileTrue(elevator.manualControl(() -> 0.5));
operator.b().whileTrue(elevator.manualControl(() ->-0.1));
/*
//Operator inputs
operator.povUp().onTrue(
moveManipulator(
@ -158,6 +176,8 @@ public class RobotContainer {
operator.b().onTrue(
algaeIntakeRoutine(false)
);
*/
}
private void configureNamedCommands() {
@ -198,6 +218,9 @@ public class RobotContainer {
sensorTab.addDouble("gyro angle", drivetrain::getGyroValue);
sensorTab.addBoolean("bottom limit switch", elevator::getBottomLimitSwitch);
sensorTab.addDouble("elevator position", elevator::getEncoderPosition);
/*
sensorTab.addBoolean("Algae Sensor", manipulator::getAlgaePhotoSwitch)
@ -220,7 +243,7 @@ public class RobotContainer {
ElevatorConstants.kCoralIntakePosition,
ManipulatorPivotConstants.kCoralIntakePosition
)
.andThen(manipulator.runUntilCollected(1));
.andThen(manipulator.runUntilCollected(() -> 1));
}
/**
@ -234,7 +257,7 @@ public class RobotContainer {
l2 ? ElevatorConstants.kL2AlgaePosition : ElevatorConstants.kL3AlgaePosition,
l2 ? ManipulatorPivotConstants.kL2AlgaePosition : ManipulatorPivotConstants.kL3AlgaePosition
)
.andThen(manipulator.runUntilCollected(1));
.andThen(manipulator.runUntilCollected(() -> 1));
}
/**

View File

@ -22,10 +22,10 @@ public class DrivetrainConstants {
public static final double kWheelBase = Units.inchesToMeters(24.5);
// Angular offsets of the modules relative to the chassis in radians
public static final double kFrontLeftChassisAngularOffset = -Math.PI / 2;
public static final double kFrontRightChassisAngularOffset = 0;
public static final double kBackLeftChassisAngularOffset = Math.PI;
public static final double kBackRightChassisAngularOffset = Math.PI / 2;
public static final double kFrontLeftChassisAngularOffset = Math.PI;
public static final double kFrontRightChassisAngularOffset = -Math.PI / 2;
public static final double kBackLeftChassisAngularOffset = Math.PI / 2;
public static final double kBackRightChassisAngularOffset = 0;
// 1, 7, 10 is the default for these three values
public static final double kSysIDDrivingRampRate = 1;

View File

@ -21,7 +21,7 @@ public class ElevatorConstants {
public static final int kCurrentLimit = 40;
public static final double kPositionControllerP = 0;
public static final double kPositionControllerP = 0.2;
public static final double kPositionControllerI = 0;
public static final double kPositionControllerD = 0;
@ -73,7 +73,8 @@ public class ElevatorConstants {
static {
motorConfig
.smartCurrentLimit(kCurrentLimit)
.idleMode(kIdleMode);
.idleMode(kIdleMode)
.inverted(false);
motorConfig.encoder
.positionConversionFactor(kEncoderConversionFactor);
motorConfig.closedLoop

View File

@ -4,8 +4,7 @@ import com.revrobotics.spark.config.SparkMaxConfig;
public class ManipulatorConstants {
public static final int kManipulatorMotorID = 12;
public static final int kCoralBeamBreakID = 1;
public static final int kAlgaeBeamBreakID = 2;
public static final int kCoralBeamBreakID = 2;
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
}

View File

@ -1,5 +1,6 @@
package frc.robot.subsystems;
import java.util.ResourceBundle.Control;
import java.util.function.DoubleSupplier;
import com.revrobotics.RelativeEncoder;
@ -7,6 +8,7 @@ import com.revrobotics.spark.ClosedLoopSlot;
import com.revrobotics.spark.SparkBase;
import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ControlType;
import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
@ -78,7 +80,7 @@ public class Elevator extends SubsystemBase {
@Override
public void periodic() {
if (getBottomLimitSwitch()) {
if (!getBottomLimitSwitch()) {
encoder.setPosition(0);
}
}
@ -139,8 +141,7 @@ public class Elevator extends SubsystemBase {
public Command manualControl(DoubleSupplier speed){
return run(() -> {
elevatorMotor1.setVoltage(feedForward.calculate(0) + (speed.getAsDouble()/12));
elevatorClosedLoop.setReference(speed.getAsDouble(), ControlType.kDutyCycle);
});
}
@ -166,7 +167,7 @@ public class Elevator extends SubsystemBase {
SparkBase.ControlType.kMAXMotionPositionControl,
ClosedLoopSlot.kSlot0,
feedForward.calculate(0)
);
);
});
/*
@ -211,6 +212,7 @@ public class Elevator extends SubsystemBase {
return encoder.getPosition();
}
/**
* Returns the value of the bottom limit switch on the elevator (false = disabled, true = enabled)
*

View File

@ -69,12 +69,12 @@ public class Manipulator extends SubsystemBase {
* @param coral Is the object a coral? (True = Coral, False = Algae)
* @return Returns a command that sets the speed of the motor
*/
public Command runUntilCollected(double speed) {
public Command runUntilCollected(DoubleSupplier speed) {
return run(() -> {
manipulatorMotor.set(
speed * -1
speed.getAsDouble()
);
}).until(() -> coralBeamBreak.get());
}).until(() -> !coralBeamBreak.get());
}
public boolean getCoralBeamBreak() {