Skip to content

Commit f62839e

Browse files
author
Robotics
committed
merged winch with some nice lab changes
2 parents 73016ce + 544ffd5 commit f62839e

File tree

5 files changed

+68
-20
lines changed

5 files changed

+68
-20
lines changed

FRC2020/src/main/java/frc/robot/OI.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,9 @@ public double getLeftSpeed() {
3838
// System.out.println("getleftspeed.getY()=" + leftStick.getY() + "
3939
// Math.pow(gety),3)=" + Math.pow(leftStick.getY(), 3));
4040
if (leftStick.getY() > 0.01) {
41-
return Math.pow(leftStick.getY(), 3) - 0.01;
41+
return 0.5 * Math.pow(leftStick.getY(), 3) - 0.01;
4242
} else if (leftStick.getY() <= -0.01) {
43-
return Math.pow(leftStick.getY(), 3) + 0.01;
43+
return 0.5 * Math.pow(leftStick.getY(), 3) + 0.01;
4444
} else {
4545
return 0.0;
4646
}
@@ -50,9 +50,9 @@ public double getRightSpeed() {
5050
// System.out.println("getrightspeed.getY()=" + rightStick.getY() +
5151
// "Math.pow(rightstickvalue)=" + Math.pow(rightStick.getY(), 3));
5252
if (rightStick.getY() > 0.01) {
53-
return -1.0 * Math.pow(rightStick.getY(), 3) + 0.01;
53+
return 0.5 * -1.0 * Math.pow(rightStick.getY(), 3) + 0.01;
5454
} else if (rightStick.getY() < -0.01) {
55-
return -1.0 * Math.pow(rightStick.getY(), 3) - 0.01;
55+
return 0.5 * -1.0 * Math.pow(rightStick.getY(), 3) - 0.01;
5656
} else {
5757
return 0.0;
5858
}

FRC2020/src/main/java/frc/robot/Robot.java

Lines changed: 8 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
import edu.wpi.first.wpilibj.DriverStation;
1313
import frc.robot.commands.DriveWithJoysticks;
1414
import frc.robot.commands.Detector;
15+
import frc.robot.commands.Shootball;
1516
import frc.robot.subsystems.DriveTrain;
1617
import frc.robot.subsystems.Shooter;
1718
import frc.robot.subsystems.Winch;
@@ -21,14 +22,16 @@
2122
import com.revrobotics.ColorMatchResult;
2223

2324
public class Robot extends TimedRobot {
25+
2426
XboxController xbox = RobotMap.xboxController;
2527
Joystick leftstick = RobotMap.leftJoystick;
2628
Joystick rightstick = RobotMap.rightJoystick;
2729

2830
public static DriveTrain driveTrain;
31+
public static Shooter shooter;
2932
public static OI OI;
3033
public static String colorString;
31-
34+
3235
double shooterVel;
3336
boolean Xon = false;
3437
boolean GreenLED_ON = false;
@@ -92,6 +95,8 @@ public void teleopInit() {
9295
RobotMap.GreenLED.set(Relay.Value.kOn);
9396
RobotMap.GreenLED.set(Relay.Value.kReverse);
9497

98+
Scheduler.getInstance().add(new Shootball());
99+
95100
// Init OI
96101
OICommands();
97102
}
@@ -125,6 +130,8 @@ public void robotPeriodic() {
125130
SmartDashboard.putNumber("Rotations Completed", ColorCycle.colorCycleValue);
126131
SmartDashboard.putNumber("Colors Passed", ColorCycle.colorsPassedValue);
127132
SmartDashboard.putNumber("Shooter Velocity", -1 * shooterVel);
133+
SmartDashboard.putNumber("Top Limit switch", RobotMap.topLimitSwitch.get() ? 1:0); // converts boolean to int
134+
SmartDashboard.putNumber("Bottom Limit Switch", RobotMap.bottomLimitSwitch.get() ? 1:0);
128135

129136
if (ColorCycle.colorCycleValue == 3) {
130137
ColorCycle.colorCycleStop();
@@ -174,21 +181,6 @@ public void teleopPeriodic() {
174181
}
175182
}
176183

177-
if (OI.shoot() == true) {
178-
for (shooterCycle = 0; shooterCycle < 500; shooterCycle++) {
179-
Shooter.initiateShot(OI.valueShooterSpeed);
180-
System.out.println("Ramping up shooter");
181-
shooterVel = RobotMap.CANCoder.getVelocity();
182-
if (shooterCycle >= 100) {
183-
Shooter.loadingShot();
184-
System.out.println("loading ball for shooting");
185-
}
186-
}
187-
} else {
188-
Shooter.shooterStop();
189-
shooterVel = RobotMap.CANCoder.getVelocity();
190-
}
191-
192184
if (OI.changeShooterSpeed() == 1) {
193185
if (OI.valueShooterSpeed < 1) {
194186
OI.valueShooterSpeed = OI.valueShooterSpeed + 0.02;
Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
package frc.robot.commands;
2+
3+
import edu.wpi.first.wpilibj.command.Command;
4+
//import frc.robot.Robot;
5+
import frc.robot.subsystems.Shooter;
6+
import frc.robot.OI;
7+
8+
9+
public class Shootball extends Command {
10+
OI oi = new OI();
11+
12+
public Shootball() {
13+
14+
}// divide distance sensor volatge by 0.997
15+
16+
protected void initialize() {
17+
18+
}
19+
20+
protected void execute() {
21+
22+
if (oi.shoot() == true) {
23+
for (int shooterCycle = 0; shooterCycle < 200; shooterCycle++) {
24+
Shooter.initiateShot(oi.valueShooterSpeed);
25+
System.out.println("Ramping up shooter");
26+
//double shooterVel = Shooter.getVelocity();
27+
if (shooterCycle >= 100) {
28+
Shooter.loadingShot();
29+
System.out.println("loading ball for shooting");
30+
}
31+
}
32+
} else {
33+
Shooter.shooterStop();
34+
}
35+
36+
}
37+
38+
protected boolean isFinished() {
39+
return false;
40+
}
41+
42+
protected void end() {
43+
}
44+
45+
protected void interrupted() {
46+
47+
}
48+
}

FRC2020/src/main/java/frc/robot/subsystems/Shooter.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ public void initDefaultCommand() {
99
// Set the default command for a subsystem here.
1010
}
1111

12+
1213
//starts up shooter motor and lets it speed up
1314
public static void initiateShot(double speed) {
1415
RobotMap.Shooter.set(speed);
@@ -23,4 +24,8 @@ public static void loadingShot(){
2324
public static void shooterStop() {
2425
RobotMap.Shooter.set(0);
2526
}
27+
28+
public static double getVelocity() {
29+
return RobotMap.CANCoder.getVelocity();
30+
}
2631
}

FRC2020/src/main/java/frc/robot/subsystems/Winch.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,14 @@ public void initDefaultCommand() {
1212
// winch up
1313
public static void winchUp() {
1414
RobotMap.Winch.set(1.0);
15+
System.out.println("winchup");
1516
}
1617

1718
// winch down
1819
public static void winchDown() {
1920
RobotMap.Winch.set(-1.0);
21+
System.out.println("winchdown");
22+
2023
}
2124

2225
public static void winchStop() {

0 commit comments

Comments
 (0)