Skip to content

Commit

Permalink
Merge branch 'Pathfinding' of https://github.com/Tigerbotics7125/FRC2024
Browse files Browse the repository at this point in the history
 into Pathfinding
  • Loading branch information
DAflamingFOX committed Mar 22, 2024
2 parents dd61264 + c113a2d commit 60f4dfe
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 15 deletions.
3 changes: 1 addition & 2 deletions src/main/java/io/github/tigerbotics7125/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -25,7 +26,6 @@
import io.github.tigerbotics7125.subsystems.Intake;
import io.github.tigerbotics7125.subsystems.Shooter;
import java.util.Map;
import edu.wpi.first.wpilibj.Timer;

public class Robot extends TimedRobot {

Expand Down Expand Up @@ -131,7 +131,6 @@ public void robotInit() {
@Override
public void robotPeriodic() {
CommandScheduler.getInstance().run();


SmartDashboard.putData("DTControlType", m_driveControlChooser);
}
Expand Down
24 changes: 11 additions & 13 deletions src/main/java/io/github/tigerbotics7125/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@ public Drivetrain() {

m_leftEncoder.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);
m_rightEncoder.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Relative);


REVUtil.retryFailable(5, () -> m_backLeft.follow(m_frontLeft));
REVUtil.retryFailable(5, () -> m_backRight.follow(m_frontRight));
Expand Down Expand Up @@ -146,8 +145,8 @@ public Command setIdleMode(IdleMode idleMode) {
public void periodic() {
SmartDashboard.putNumber("/DT/Left", m_frontLeft.get());
SmartDashboard.putNumber("/DT/Right", m_frontRight.get());
SmartDashboard.putNumber("Left Motor Value",getLeftPositionMeters());
SmartDashboard.putNumber("Right Motor Value",getRightPositionMeters());
SmartDashboard.putNumber("Left Motor Value", getLeftPositionMeters());
SmartDashboard.putNumber("Right Motor Value", getRightPositionMeters());

m_odometry.update(
m_gyro.getRotation2d(),
Expand Down Expand Up @@ -196,19 +195,18 @@ private void driveRelative(ChassisSpeeds chassisSpeeds) {
m_frontLeft.set(
m_leftPID.calculate(getLeftVelocityMetersPerSecond(), ws.leftMetersPerSecond));
m_frontRight.set(
m_rightPID.calculate(getRightVelocityMetersPerSecond(),
ws.rightMetersPerSecond));
m_rightPID.calculate(getRightVelocityMetersPerSecond(), ws.rightMetersPerSecond));

//m_frontLeft.set(ws.leftMetersPerSecond / Constants.DriveTrain.kMaxLinearVelocity);
//m_frontRight.set(ws.rightMetersPerSecond / Constants.DriveTrain.kMaxLinearVelocity);
// m_frontLeft.set(ws.leftMetersPerSecond / Constants.DriveTrain.kMaxLinearVelocity);
// m_frontRight.set(ws.rightMetersPerSecond / Constants.DriveTrain.kMaxLinearVelocity);
}
public Command resetEncoders(){

public Command resetEncoders() {
return runOnce(
()->{
m_leftEncoder.setSelectedSensorPosition(0);
m_rightEncoder.setSelectedSensorPosition(0);
}
);
() -> {
m_leftEncoder.setSelectedSensorPosition(0);
m_rightEncoder.setSelectedSensorPosition(0);
});
}
public Command resetGyro(){
return runOnce(
Expand Down

0 comments on commit 60f4dfe

Please sign in to comment.