Random changes to try to make the robot work
This commit is contained in:
parent
187e7385c8
commit
2275248f70
@ -129,11 +129,13 @@ public class RobotContainer {
|
||||
driver.povLeft().whileTrue(climberRollers.runRoller(0.5));
|
||||
driver.povRight().whileTrue(climberRollers.runRoller(-0.5));
|
||||
|
||||
operator.povUp().whileTrue(elevator.goToSetpoint(30.0));
|
||||
operator.povUp().whileTrue(
|
||||
elevator.goToSetpoint(20)
|
||||
);
|
||||
|
||||
operator.a().whileTrue(elevator.manualControl(() -> 0.5));
|
||||
//operator.a().whileTrue(elevator.manualControl(() -> 0.5));
|
||||
|
||||
operator.b().whileTrue(elevator.manualControl(() ->-0.1));
|
||||
//operator.b().whileTrue(elevator.manualControl(() ->-0.1));
|
||||
|
||||
/*
|
||||
//Operator inputs
|
||||
|
@ -21,7 +21,7 @@ public class ElevatorConstants {
|
||||
|
||||
public static final int kCurrentLimit = 40;
|
||||
|
||||
public static final double kPositionControllerP = 0.2;
|
||||
public static final double kPositionControllerP = 0.3;
|
||||
public static final double kPositionControllerI = 0;
|
||||
public static final double kPositionControllerD = 0;
|
||||
|
||||
@ -87,4 +87,15 @@ public class ElevatorConstants {
|
||||
.maxVelocity(kMaxVelocity)
|
||||
.allowedClosedLoopError(kAllowedError);
|
||||
}
|
||||
|
||||
public static final SparkMaxConfig motorConfig2 = new SparkMaxConfig();
|
||||
|
||||
static {
|
||||
motorConfig2
|
||||
.smartCurrentLimit(kCurrentLimit)
|
||||
.idleMode(kIdleMode)
|
||||
.inverted(false);
|
||||
motorConfig.encoder
|
||||
.positionConversionFactor(kEncoderConversionFactor);
|
||||
}
|
||||
}
|
||||
|
@ -6,7 +6,6 @@ import com.revrobotics.spark.SparkBase.PersistMode;
|
||||
import com.revrobotics.spark.SparkBase.ResetMode;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ClimberPivotConstants;
|
||||
|
@ -1,6 +1,5 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.ResourceBundle.Control;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.revrobotics.RelativeEncoder;
|
||||
@ -43,16 +42,16 @@ public class Elevator extends SubsystemBase {
|
||||
MotorType.kBrushless
|
||||
);
|
||||
|
||||
elevatorClosedLoop = elevatorMotor1.getClosedLoopController();
|
||||
|
||||
elevatorMotor1.configure(
|
||||
ElevatorConstants.motorConfig,
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
|
||||
elevatorClosedLoop = elevatorMotor1.getClosedLoopController();
|
||||
|
||||
elevatorMotor2.configure(
|
||||
ElevatorConstants.motorConfig.follow(ElevatorConstants.kElevatorMotor1ID),
|
||||
ElevatorConstants.motorConfig2.follow(ElevatorConstants.kElevatorMotor1ID),
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
|
Loading…
Reference in New Issue
Block a user