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

Commit

Permalink
cleveland
Browse files Browse the repository at this point in the history
h
  • Loading branch information
TheGamer1002 committed Mar 30, 2023
1 parent e377eac commit c44bd68
Show file tree
Hide file tree
Showing 13 changed files with 135 additions and 131 deletions.
Binary file added FRC_20230330_144215.wpilog
Binary file not shown.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2023.4.2"
id "edu.wpi.first.GradleRIO" version "2023.4.3"
}

repositories {
Expand Down
32 changes: 5 additions & 27 deletions final-final-final.json
Original file line number Diff line number Diff line change
Expand Up @@ -120,34 +120,12 @@
"Crosshair/Crosshair color": "#FFFFFFFF",
"Controls/Show controls": true,
"Controls/Rotation": "NONE",
"compression": 35.0,
"compression": 27.078429483899882,
"fps": 15,
"imageWidth": 640,
"imageHeight": 480
}
},
"25,8": {
"size": [
7,
7
],
"content": {
"_type": "Graph",
"_source0": "network_table:///FMSInfo/FMSControlData",
"_source1": "network_table:///Shuffleboard/PDP/PDP/Voltage",
"_title": "Voltage",
"_glyph": 148,
"_showGlyph": false,
"Graph/Visible time": 60.0,
"Graph/X-axis auto scrolling": true,
"Y-axis/Automatic bounds": false,
"Y-axis/Upper bound": 13.0,
"Y-axis/Lower bound": 6.0,
"Y-axis/Unit": "v",
"Visible data/FMSInfo/FMSControlData": true,
"Visible data/Shuffleboard/PDP/PDP/Voltage": true
}
},
"24,0": {
"size": [
3,
Expand Down Expand Up @@ -498,9 +476,9 @@
}
],
"windowGeometry": {
"x": -7.199999809265137,
"y": -7.199999809265137,
"width": 1550.4000244140625,
"height": 838.4000244140625
"x": -6.400000095367432,
"y": 1.600000023841858,
"width": 1547.199951171875,
"height": 828.7999877929688
}
}
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ public class RobotContainer {
private final DecreaseMaxSpeedCommand m_DecreaseMaxSpeedCommand =
new DecreaseMaxSpeedCommand(m_Tank);
private final FineDriveCommand m_FineDriveCommand = new FineDriveCommand(m_Tank);
private final PlaceCubeSecondLevelCommand m_PlaceCubeSecondLevelCommand = new PlaceCubeSecondLevelCommand(m_Tank, m_Arm, m_Claw);

private GenericEntry timeWidget = Shuffleboard.getTab("stuff").add("time", 0).withWidget("Match Time").getEntry();

Expand All @@ -73,6 +74,7 @@ public RobotContainer() {
tab.add(m_IncreaseMaxSpeedCommand);
tab.add(m_MoveArmYCommand);
tab.add(m_PDP);
tab.add(m_PlaceCubeSecondLevelCommand);



Expand Down Expand Up @@ -106,6 +108,8 @@ private void configureButtonBindings() {
// .whileTrue(m_OpenClawCommand);
new JoystickButton(m_armController2, XboxController.Button.kLeftBumper.value)
.whileTrue(m_FineDriveCommand);
new JoystickButton(m_armController2, XboxController.Button.kY.value).whileTrue(m_PlaceConeSecondLevelCommand);

// new JoystickButton(m_armController2, XboxController.Button.kB.value)
// .whileTrue(m_PlaceConeSecondLevelCommand);
}
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/robot/commands/AutoCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,14 @@ public class AutoCommand extends SequentialCommandGroup {
public AutoCommand(PID m_pid, Tank m_driveBase, Arm m_arm, Claw m_claw) {
addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm, m_claw), new BalanceCommand(m_pid, m_driveBase));

//side autonomous
//addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm, m_claw));

//middle autonomous
//addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm, m_claw), new BalanceCommand(m_pid, m_driveBase));


// new BalanceCommand(m_pid, m_driveBase)
// new PlaceCubeFirstLevelCommand(m_driveBase, m_claw, m_arm)
// new PlaceConeSecondLevelCommand(m_driveBase, m_arm)
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/MoveArmYCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public void initialize() {}

@Override
public void execute() {
m_subsystem.moveArm(-RobotContainer.getControllerLeftStickY());
m_subsystem.moveArm(RobotContainer.getControllerLeftStickY());
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ public void execute() {
if (firstStep) {
if (Math.abs(arm.armMotor.getEncoder().getPosition()) < 115) {
claw.closeClaw();
arm.armMotor.set(0.4);
arm.armMotor.set(0.5);
}

if (Math.abs(arm.armMotor.getEncoder().getPosition()) >= 115) {
Expand All @@ -49,13 +49,13 @@ public void execute() {
}

// go over charge station
if (Math.abs(drive.getAverageDistance()) < 4.8 && firstStep == false) {
if (Math.abs(drive.getAverageDistance()) < 4.95 && firstStep == false) {
claw.stopClaw();
drive.setAllMotors(-0.3); // move back so that cone falls in
arm.armMotor.set(-0.45);
arm.armMotor.set(-0.5);
}

if (Math.abs(drive.getAverageDistance()) >= 4.8) {
if (Math.abs(drive.getAverageDistance()) >= 4.95) {
drive.setAllMotors(0);
}
}
Expand All @@ -75,6 +75,6 @@ public void end(boolean interrupted) {

@Override
public boolean isFinished() {
return Math.abs(drive.getAverageDistance()) >= 4.8;
return Math.abs(drive.getAverageDistance()) >= 4.95;
}
}
92 changes: 92 additions & 0 deletions src/main/java/frc/robot/commands/PlaceCubeSecondLevelCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
// 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.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.*;

public class PlaceCubeSecondLevelCommand extends CommandBase {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final Tank drive;
private final Claw claw;
private final Arm arm;
private GenericEntry widget;

private boolean firstStep = true;

public PlaceCubeSecondLevelCommand(Tank drive, Arm arm, Claw claw) {
this.drive = drive;
this.arm = arm;
this.claw = claw;
addRequirements(drive);
addRequirements(arm);



}

@Override
public void initialize() {
/* drive.leftFront.getEncoder().setPosition(0);
drive.leftRear.getEncoder().setPosition(0);
drive.rightFront.getEncoder().setPosition(0);
drive.rightRear.getEncoder().setPosition(0); */

arm.armMotor.getEncoder().setPosition(0);
widget = Shuffleboard.getTab("stuff").add("arm thing", arm.armMotor.getEncoder().getPosition()).getEntry();

}

// double check constants
@Override
public void execute() {
widget.setDouble(arm.armMotor.getEncoder().getPosition());

if (firstStep) {
claw.closeClaw();
arm.armMotor.set(0.25);
}


if (arm.armMotor.getEncoder().getPosition() >= 60) {
firstStep = false;
arm.armMotor.set(0);
arm.armMotor.getEncoder().setPosition(0);
claw.openClaw();
}

// go over charge station
/* if (Math.abs(drive.getAverageDistance()) < 4.95 && firstStep == false) {
claw.stopClaw();
drive.setAllMotors(-0.3); // move back so that cone falls in
arm.armMotor.set(-0.5);
}
if (Math.abs(drive.getAverageDistance()) >= 4.95) {
drive.setAllMotors(0);
} */

}

@Override
public void end(boolean interrupted) {
/* drive.leftFront.getEncoder().setPosition(0);
drive.leftRear.getEncoder().setPosition(0);
drive.rightFront.getEncoder().setPosition(0);
drive.rightRear.getEncoder().setPosition(0); */
arm.armMotor.getEncoder().setPosition(0);

//drive.setAllMotors(0);
arm.armMotor.set(0); // stop the arm motor
}

@Override
public boolean isFinished() {
/* return Math.abs(drive.getAverageDistance()) >= 4.95; */
return false;
}
}
11 changes: 11 additions & 0 deletions src/main/java/frc/robot/subsystems/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

import com.revrobotics.CANSparkMax.IdleMode;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;

import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -21,19 +23,28 @@ public class Arm extends SubsystemBase {

public double gearRatio = 87;


public GenericEntry encoderWidget;

public Arm() {
armMotor = new CANSparkMax(7, MotorType.kBrushless);
armMotor.setIdleMode(IdleMode.kBrake);
armMotor.setSmartCurrentLimit(30, 40);
armMotor.burnFlash();
addChild("Arm Motor", armMotor);

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


Shuffleboard.getTab("Motors").add("Arm", armMotor);

}

@Override
public void periodic() {
SmartDashboard.putBoolean("zeroDeg", allTheWayDownRear.get());

encoderWidget.setDouble(armMotor.getEncoder().getPosition());
}

public void moveArm(double leftStickYaxis) {
Expand Down
23 changes: 3 additions & 20 deletions src/main/java/frc/robot/subsystems/Claw.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,11 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.RobotContainer;
import frc.robot.Interfaces.*;
import java.util.Map;


public class Claw extends SubsystemBase {
public CANSparkMax clawMotor;

private GenericEntry stallWidget;
private GenericEntry freeWidget;
private ShuffleboardLayout layout;

// gear ratio is 100:1

Expand All @@ -36,20 +33,6 @@ public Claw() {

Shuffleboard.getTab("Motors").add("Claw", clawMotor);

layout = Shuffleboard.getTab("Config").getLayout("Claw", BuiltInLayouts.kList);

stallWidget =
layout
.add("Stall Limit", 10)
.withWidget(BuiltInWidgets.kNumberSlider)
.withProperties(Map.of("min", 0, "max", 20))
.getEntry();
freeWidget =
layout
.add("Free Limit", 11)
.withWidget(BuiltInWidgets.kNumberSlider)
.withProperties(Map.of("min", 0, "max", 20))
.getEntry();
}

@Override
Expand All @@ -58,11 +41,11 @@ public void periodic() {
}

public void closeClaw() {
clawMotor.set(0.7);
clawMotor.set(1);
}

public void openClaw() {
clawMotor.set(-0.7);
clawMotor.set(-1);
}

public void stopClaw() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/PDP.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ public PDP() {
@Override
public void periodic() {
// This method will be called once per scheduler run
SmartDashboard.putNumber("PDP Voltage", pdp.getVoltage());

}
/**
* @return the voltage of the PDP in Volts
Expand Down
7 changes: 1 addition & 6 deletions src/main/java/frc/robot/subsystems/PID.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,16 +25,14 @@ public class PID extends SubsystemBase {

private float initPitch;

public PIDController pidController;

public PID() {
toleranceDeg = 0.5;
iLimit = 2.0;


initPitch = gyro.getPitch();
pidController = new PIDController(P, I, D);
addChild("PID Controller", pidController);

}

@Override
Expand Down Expand Up @@ -69,9 +67,6 @@ public double PIDoutput() {
I = kI * errorSum;
D = kD * errorRate;

pidController.setP(P);
pidController.setI(I);
pidController.setD(D);

double outputSpeed = P + I + D;

Expand Down
Loading

0 comments on commit c44bd68

Please sign in to comment.