-
Notifications
You must be signed in to change notification settings - Fork 1
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
Fix/intake #24
Changes from all commits
11f9b0c
b029644
640685f
f2873ee
71f19f5
c34ade4
82c0640
32b7e6d
624c997
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
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 | ||
} | ||
} |
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
---|---|---|
|
@@ -11,6 +11,6 @@ | |
}, | ||
"rampRate": { | ||
"drive": 0.25, | ||
"angle": 0.25 | ||
"angle": 0 | ||
} | ||
} |
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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? |
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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 |
---|---|---|
@@ -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) { | ||
m_FlyWSubsystem.enableflywheelfast(); | ||
// TODO: Change this to the correct button | ||
} else if (ConveyorJoystick.getRawButton(8) == true) { | ||
m_FlyWSubsystem.reverseflywheel(); | ||
System.out.println("Conveyor Moving in Reverse"); | ||
} else if (ConveyorJoystick.getRawButton(9) == true) { | ||
m_FlyWSubsystem.enableflywheelslow(); | ||
} else { | ||
m_FlyWSubsystem.disableflywheel(); | ||
} | ||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
m_FlyWSubsystem.disableflywheel(); | ||
} | ||
|
||
@Override | ||
public boolean isFinished() { | ||
return false; | ||
} | ||
} |
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 | ||
} | ||
} |
There was a problem hiding this comment.
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.