Skip to content
This repository has been archived by the owner on Jan 10, 2024. It is now read-only.

Commit

Permalink
fixing stuff maybe ?
Browse files Browse the repository at this point in the history
  • Loading branch information
TheGamer1002 committed Apr 18, 2023
1 parent 9f72f04 commit 595db20
Show file tree
Hide file tree
Showing 13 changed files with 480 additions and 90 deletions.
Binary file added FRC_20230418_172752.wpilog
Binary file not shown.
4 changes: 4 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
"/FMSInfo": "FMSInfo",
"/LiveWindow/Tank/All": "Motor Controller",
"/LiveWindow/Tank/Drive": "DifferentialDrive",
"/LiveWindow/Tank/Gyro": "Gyro",
"/LiveWindow/Ungrouped/DigitalInput[1]": "Digital Input",
"/LiveWindow/Ungrouped/navX-Sensor[4]": "Gyro",
"/Shuffleboard/Driver/Gyro": "Gyro",
Expand Down Expand Up @@ -82,6 +83,9 @@
"/SmartDashboard/Field": {
"Robot": {
"style": "Track"
},
"window": {
"visible": true
}
},
"/SmartDashboard/Scheduler": {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Interfaces/CANSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -462,11 +462,11 @@ public double getMaxOutputRange() {
// absolute encoder stuff
public double getAbsoluteEncoderPosition() {
throwIfClosed();
return getAlternateEncoder(4096).getPosition();
return getAbsoluteEncoder(Type.kDutyCycle).getPosition();
}
public double getAbsoluteEncoderVelocity() {
throwIfClosed();
return getAlternateEncoder(4096).getVelocity();
return getAbsoluteEncoder(Type.kDutyCycle).getVelocity();
}


Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/commands/DriveCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ public class DriveCommand extends CommandBase {
@SuppressWarnings({ "PMD.UnusedPrivateField", "PMD.SingularField" })
private final Tank m_drivebase;

private boolean isFinishedVar = false;




Expand Down Expand Up @@ -47,9 +49,11 @@ public void end(boolean interrupted) {

@Override
public boolean isFinished() {
// we need to return the value in Constants.isDriveCommandFinished but in a static way while keeping the value non-static in Constants
private static final boolean x = Constants.isDriveCommandFinished;
return x;
return isFinishedVar;
}

public void setFinished(boolean x) {
isFinishedVar = x;
}

@Override
Expand Down
38 changes: 38 additions & 0 deletions src/main/java/frc/robot/commands/PickUpPieceCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.Claw;

public class PickUpPieceCommand extends CommandBase {
/** Creates a new PickUpPieceCommand. */
private Claw m_Claw;
public PickUpPieceCommand(Claw claw) {
// Use addRequirements() here to declare subsystem dependencies.
m_Claw = claw;
addRequirements(claw);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
m_Claw.clawMotor.set(0.5);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
21 changes: 0 additions & 21 deletions src/main/java/frc/robot/commands/Tracking.java

This file was deleted.

61 changes: 36 additions & 25 deletions src/main/java/frc/robot/commands/XTracking.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,42 +4,53 @@

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.subsystems.Tank;
import frc.robot.subsystems.Tracking.Constants;
import frc.robot.subsystems.Tracking.Target;
import frc.robot.RobotContainer;
import frc.robot.commands.*;
import frc.robot.subsystems.Tracking.Constants.xConstants;

public class XTracking extends CommandBase {
// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class XTracking extends PIDCommand {

private double tx;
/** Creates a new XTracking. */
public XTracking(Tank tank, Target target) {
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(tank, target);
}
private double kp;
private double ki;
private double kd;

// Called when the command is initially scheduled.
@Override
public void initialize() {
// stop the DriveCommand
public static double kOutput;

}
private static Tank m_tank;

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
tx = Target.getTX();
/** Creates a new XTracking. */
public XTracking(Tank tank) {

super(
// The controller that the command will use
new PIDController(Constants.xConstants.getkP(), Constants.xConstants.getkI(), Constants.xConstants.getkD()),
// This should return the measurement
Target::getTX,
// This should return the setpoint (can also be a constant)
() -> Constants.xConstants.getkSetpoint(),
// This uses the output
output -> {
// Use the output here
kOutput = output;

m_tank.arcadeDrive(YTracking.kOutput, output);
});
addRequirements(tank);
m_tank = tank;
// Use addRequirements() here to declare subsystem dependencies.
// Configure additional PID options by calling `getController` here.
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
return Constants.xConstants.getLowerBound() < (Target.getTX() - Constants.xConstants.getkSetpoint())
&& (Target.getTX() - Constants.xConstants.getkSetpoint()) < Constants.xConstants.getUpperBound();
}
}
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/commands/YTracking.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.subsystems.Tank;
import frc.robot.subsystems.Tracking.Constants;
import frc.robot.subsystems.Tracking.Target;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
public class YTracking extends PIDCommand {
public static double kOutput;
/** Creates a new YTracking. */
public YTracking() {
super(
// The controller that the command will use
new PIDController(Constants.yConstants.getkP(), Constants.yConstants.getkI(), Constants.yConstants.getkD()),
// This should return the measurement
Target::getTY,
// This should return the setpoint (can also be a constant)
() -> Constants.yConstants.getkSetpoint(),
// This uses the output
output -> {
// Use the output here
kOutput = output;
Tank.arcadeDrive(XTracking.kOutput, output);
});
// Use addRequirements() here to declare subsystem dependencies.
// Configure additional PID options by calling `getController` here.
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.REVPhysicsSim;
import com.revrobotics.SparkMaxAlternateEncoder;
import com.revrobotics.SparkMaxPIDController;
import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
Expand Down Expand Up @@ -41,7 +42,6 @@ public class Arm extends SubsystemBase {

public AbsoluteEncoder encoder;


public Arm() {

kP = 0.0001;
Expand All @@ -58,6 +58,7 @@ public Arm() {
armMotor.setIdleMode(IdleMode.kBrake);
armMotor.setSmartCurrentLimit(30, 40);
armMotor.burnFlash();
// set
addChild("Arm Motor", armMotor);

armPID = armMotor.getPIDController();
Expand All @@ -68,8 +69,12 @@ public Arm() {
armPID.setIZone(kIz);
armPID.setFF(kFF);
armPID.setOutputRange(kMinOutput, kMaxOutput);

// set the spark max to alternate encoder mode

AbsoluteEncoder encoder = armMotor.getAbsoluteEncoder(Type.kDutyCycle);

// configure the data port on top to be used with the REV Through Bore Encoder using the absolute encoder adapter
encoder = armMotor.getAbsoluteEncoder(Type.kDutyCycle);

encoderWidget = Shuffleboard.getTab("Motors").add("Arm Encoder", armMotor.getEncoder().getPosition()).getEntry();

Expand Down Expand Up @@ -99,8 +104,6 @@ public void moveArm(double value) {
armMotor.set(motorDrive);
}



@Override
public void simulationPeriodic() {
// This method will be called once per scheduler run during simulation
Expand Down
Loading

0 comments on commit 595db20

Please sign in to comment.