Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix/intake #24

Merged
merged 9 commits into from
Mar 8, 2024
4 changes: 2 additions & 2 deletions src/main/deploy/swerve/controllerproperties.json
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are the PIDs and deadbands correct? The deadband now becomes hyper sensitive and the derivative heading is now zero.

Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
{
"angleJoystickRadiusDeadband": 0.25,
"angleJoystickRadiusDeadband": 0.05,
"heading": {
"p": 0.4,
"i": 0,
"d": 0.01
"d": 0
}
}
4 changes: 2 additions & 2 deletions src/main/deploy/swerve/modules/backleft.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"location": {
"front": -13.5,
"left": 13.5
"front": -11,
"left": 11
},
"absoluteEncoderOffset": 276.15234375,
"drive": {
Expand Down
4 changes: 2 additions & 2 deletions src/main/deploy/swerve/modules/backright.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"location": {
"front": -13.5,
"left": -13.5
"front": -11,
"left": -11
},
"absoluteEncoderOffset": 299.267578125,
"drive": {
Expand Down
4 changes: 2 additions & 2 deletions src/main/deploy/swerve/modules/frontleft.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"location": {
"front": 13.5,
"left": 13.5
"front": 11,
"left": 11
},
"absoluteEncoderOffset": 357.978515625,
"drive": {
Expand Down
4 changes: 2 additions & 2 deletions src/main/deploy/swerve/modules/frontright.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"location": {
"front": 13.5,
"left": -13.5
"front": 11,
"left": -11
},
"absoluteEncoderOffset": 52.91015625,
"drive": {
Expand Down
2 changes: 1 addition & 1 deletion src/main/deploy/swerve/modules/physicalproperties.json
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is the ramp rate zero? Is it viable to have the angle motors always run full speed instead of not ramping up to full speed?

Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,6 @@
},
"rampRate": {
"drive": 0.25,
"angle": 0.25
"angle": 0
}
}
2 changes: 1 addition & 1 deletion src/main/deploy/swerve/swervedrive.json
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why was the IMU inverted? Doesn't the navX configuration require the navX to be inverted regardless?

Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
"id": 0,
"canbus": null
},
"invertedIMU": true,
"invertedIMU": false,
"modules": [
"frontleft.json",
"frontright.json",
Expand Down
14 changes: 11 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,14 +76,22 @@ public static class MechanismConstants {
public static final int INTAKE_MOTOR_FRONT = 52;
public static final boolean INTAKE_MOTOR_SUSHI_INVERTED = true;
public static final boolean INTAKE_MOTOR_FRONT_INVERTED = false;
public static final double INTAKE_MOTOR_SPEED_FRONT = 0.8;
public static final double INTAKE_MOTOR_SPEED_FRONT = 0.2;
public static final double INTAKE_MOTOR_SPEED_SUSHI = 0.8;

// Conveyor Motors
public static final int CONVEYOR_MOTOR_1 = 1;
public static final int CONVEYOR_MOTOR_2 = 2;
public static final boolean CONVEYOR_MOTOR_1_INVERTED = true;
public static final boolean CONVEYOR_MOTOR_2_INVERTED = true;
public static final double CONVEYOR_MOTOR_SPEED = 0.30;
public static final boolean CONVEYOR_MOTOR_2_INVERTED = false;
public static final double CONVEYOR_MOTOR_SPEED = 0.38;

// Flywheel Motors
public static final int FLYWHEEL_MOTOR_1 = 3;
public static final int FLYWHEEL_MOTOR_2 = 4;
public static final boolean FLYWHEEL_MOTOR_1_INVERTED = true;
public static final boolean FLYWHEEL_MOTOR_2_INVERTED = false;
public static final double FLYWHEEL_MOTOR_SPEED = 1.0;
public static final double FLYWHEEL_MOTOR_SPEED_SLOW = 0.15;
}
}
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

None of these changes except for changing the default command actually do anything. Are you sure this was intentional?

Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@
import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.ConveyorCommand;
import frc.robot.commands.DumpControl;
import frc.robot.commands.FlyWCommand;
import frc.robot.commands.IntakeCommand;
import frc.robot.commands.swervedrive.drivebase.AbsoluteDriveAdv;
import frc.robot.subsystems.Conveyor;
import frc.robot.subsystems.Dump;
import frc.robot.subsystems.FlyWheel;
import frc.robot.subsystems.Intake;
import frc.robot.subsystems.swervedrive.SwerveSubsystem;
import java.io.File;
Expand All @@ -50,18 +52,20 @@ public class RobotContainer {
private final Intake intake = new Intake();
private final Dump dump = new Dump();
private final Conveyor conveyor = new Conveyor();
private final FlyWheel flyWheel = new FlyWheel();

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {

intake.setDefaultCommand(new IntakeCommand(intake));
dump.setDefaultCommand(new DumpControl(dump));
conveyor.setDefaultCommand(new ConveyorCommand(conveyor));
flyWheel.setDefaultCommand(new FlyWCommand(flyWheel));

// Configure the trigger bindings
configureBindings();

AbsoluteDriveAdv closedAbsoluteDriveAdv =
final AbsoluteDriveAdv closedAbsoluteDriveAdv =
new AbsoluteDriveAdv(
drivebase,
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
Expand Down Expand Up @@ -94,15 +98,15 @@ public RobotContainer() {
drivebase.driveCommand(
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRawAxis(2));
() -> driverXbox.getRightX() * 0.5);

Command driveFieldOrientedDirectAngleSim =
drivebase.simDriveCommand(
() -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND),
() -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND),
() -> driverXbox.getRawAxis(2));

drivebase.setDefaultCommand(closedAbsoluteDriveAdv);
drivebase.setDefaultCommand(driveFieldOrientedDirectAngle);
}

/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/DumpControl.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ public void initialize() {}
public void execute() {
// TODO: Change this to the correct button
if (DumpJoystick.getRawButton(1)) {
DumpSubsystem.openThenClose();
DumpSubsystem.open();
// TODO: Change this to the correct button
} else if (DumpJoystick.getRawButton(2)) {
DumpSubsystem.close();
Expand Down
50 changes: 50 additions & 0 deletions src/main/java/frc/robot/commands/FlyWCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
// 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.wpilibj.Joystick;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.FlyWheel;

public class FlyWCommand extends Command {
private final FlyWheel m_FlyWSubsystem;
// controller
// TODO: Change this to the correct controller
private final Joystick ConveyorJoystick = new Joystick(1);

public FlyWCommand(FlyWheel subsystem) {
m_FlyWSubsystem = subsystem;
addRequirements(m_FlyWSubsystem);
}

@Override
public void initialize() {}

@Override
public void execute() {
// TODO: Change this to the correct button
if (ConveyorJoystick.getRawButton(7) == true) {

Check warning on line 28 in src/main/java/frc/robot/commands/FlyWCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(7) == true` can be simplified to 'ConveyorJoystick.getRawButton(7)'
m_FlyWSubsystem.enableflywheelfast();
// TODO: Change this to the correct button
} else if (ConveyorJoystick.getRawButton(8) == true) {

Check warning on line 31 in src/main/java/frc/robot/commands/FlyWCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(8) == true` can be simplified to 'ConveyorJoystick.getRawButton(8)'
m_FlyWSubsystem.reverseflywheel();
System.out.println("Conveyor Moving in Reverse");
} else if (ConveyorJoystick.getRawButton(9) == true) {

Check warning on line 34 in src/main/java/frc/robot/commands/FlyWCommand.java

View workflow job for this annotation

GitHub Actions / qodana

Pointless boolean expression

`ConveyorJoystick.getRawButton(9) == true` can be simplified to 'ConveyorJoystick.getRawButton(9)'
m_FlyWSubsystem.enableflywheelslow();
} else {
m_FlyWSubsystem.disableflywheel();
}
}

@Override
public void end(boolean interrupted) {
m_FlyWSubsystem.disableflywheel();
}

@Override
public boolean isFinished() {
return false;
}
}
53 changes: 53 additions & 0 deletions src/main/java/frc/robot/subsystems/FlyWheel.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
// 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.subsystems;

import com.revrobotics.CANSparkLowLevel;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MechanismConstants;

public class FlyWheel extends SubsystemBase {

private final CANSparkMax flywheelMotor1 =
new CANSparkMax(MechanismConstants.FLYWHEEL_MOTOR_1, CANSparkLowLevel.MotorType.kBrushless);
private final CANSparkMax flywheelMotor2 =
new CANSparkMax(MechanismConstants.FLYWHEEL_MOTOR_2, CANSparkLowLevel.MotorType.kBrushless);

/** Creates a new flywheel. */
public FlyWheel() {
flywheelMotor1.setInverted(MechanismConstants.FLYWHEEL_MOTOR_1_INVERTED);
flywheelMotor2.setInverted(MechanismConstants.FLYWHEEL_MOTOR_2_INVERTED);
}

/** Sets the flywheel motors to 100% power. */
public void enableflywheelfast() {
flywheelMotor1.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED);
flywheelMotor2.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED);
}

/** Sets the flywheel motors to slow speed */
public void enableflywheelslow() {
flywheelMotor1.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW);
flywheelMotor2.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW);
}

/** Sets the flywheel motors to 0% power. */
public void disableflywheel() {
flywheelMotor1.set(0);
flywheelMotor2.set(0);
}

/** Sets the flywheel motors to -100% power. (Reverse direction) */
public void reverseflywheel() {
flywheelMotor1.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW);
flywheelMotor2.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}
Loading