Skip to content

Commit 02f563a

Browse files
committed
Add BrakeController utility and integrate into Robot and ModuleIOSpark
1 parent dc3b7b3 commit 02f563a

7 files changed

Lines changed: 98 additions & 4 deletions

File tree

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -190,3 +190,4 @@ src/main/java/frc/robot/BuildConstants.java
190190
# Eclipse generated file for annotation processors
191191
.factorypath
192192

193+
src/main/java/frc/robot/BuildConstants.java
Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
package com.revrobotics.spark;
2+
3+
import com.revrobotics.REVLibError;
4+
import com.revrobotics.jni.CANSparkJNI;
5+
6+
public class SparkBaseExtensions {
7+
8+
/**
9+
* Checked function for setting controller inverted.
10+
*
11+
* <p>
12+
* This call has no effect if the controller is a follower.
13+
*
14+
* @param isInverted true = inverted
15+
*/
16+
public static REVLibError setInverted(SparkBase sparkBase, boolean isInverted) {
17+
return REVLibError.fromInt(
18+
CANSparkJNI.c_Spark_SetInverted(sparkBase.sparkHandle, isInverted));
19+
}
20+
21+
/**
22+
* Enable or disable center aligned mode for the duty cycle sensor.
23+
*
24+
* @param enable true = center aligned enabled
25+
*/
26+
public static REVLibError setCenterAlignedMode(SparkBase sparkBase, boolean enable) {
27+
return REVLibError.fromInt(
28+
CANSparkJNI.c_Spark_SetParameterBool(sparkBase.sparkHandle, 152, enable));
29+
}
30+
31+
/**
32+
* Enable or disable PID voltage output mode.
33+
*
34+
* <p>
35+
* When enabled, PID output is voltage instead of duty cycle.
36+
*
37+
* @param enable true = PID voltage output
38+
*/
39+
public static REVLibError setPIDVoltageOutput(SparkBase sparkBase, boolean enable) {
40+
return REVLibError.fromInt(
41+
CANSparkJNI.c_Spark_SetParameterUint32(
42+
sparkBase.sparkHandle, 74, enable ? 1 : 0));
43+
}
44+
45+
/**
46+
* Enable or disable brake mode.
47+
*
48+
* <p>
49+
* true = Brake mode
50+
* false = Coast mode
51+
*
52+
* @param brake true = brake, false = coast
53+
*/
54+
public static REVLibError setBrakeMode(SparkBase sparkBase, boolean brake) {
55+
// 1 = Brake, 0 = Coast
56+
return REVLibError.fromInt(
57+
CANSparkJNI.c_Spark_SetParameterUint32(
58+
sparkBase.sparkHandle,
59+
6,
60+
brake ? 1 : 0));
61+
}
62+
}

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

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99

1010
import edu.wpi.first.wpilibj2.command.Command;
1111
import edu.wpi.first.wpilibj2.command.CommandScheduler;
12+
import frc.robot.util.BrakeController;
1213
import frc.robot.util.battery.BatteryUtils;
1314
import org.littletonrobotics.junction.LogFileUtil;
1415
import org.littletonrobotics.junction.LoggedRobot;
@@ -104,7 +105,9 @@ public void robotPeriodic() {
104105

105106
/** This function is called once when the robot is disabled. */
106107
@Override
107-
public void disabledInit() {}
108+
public void disabledInit() {
109+
BrakeController.setAllBrake(false);
110+
}
108111

109112
/** This function is called periodically when disabled. */
110113
@Override
@@ -114,7 +117,7 @@ public void disabledPeriodic() {}
114117
@Override
115118
public void autonomousInit() {
116119
autonomousCommand = robotContainer.getAutonomousCommand();
117-
120+
BrakeController.setAllBrake(true);
118121
// schedule the autonomous command (example)
119122
if (autonomousCommand != null) {
120123
autonomousCommand.schedule();
@@ -132,6 +135,7 @@ public void teleopInit() {
132135
// teleop starts running. If you want the autonomous to
133136
// continue until interrupted by another command, remove
134137
// this line or comment it out.
138+
BrakeController.setAllBrake(true);
135139
if (autonomousCommand != null) {
136140
autonomousCommand.cancel();
137141
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -139,7 +139,7 @@ public RobotContainer() {
139139
*/
140140
private void configureButtonBindings() {
141141

142-
PIDController aimController = new PIDController(2, 0.0, 0.0);
142+
PIDController aimController = new PIDController(1, 0.0, 0.0);
143143
aimController.enableContinuousInput(-Math.PI, Math.PI);
144144
controller
145145
.button(5)

src/main/java/frc/robot/subsystems/LedSubsystem.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
import frc.robot.util.led.Led;
1313

1414
public class LedSubsystem extends SubsystemBase {
15-
@SuppressWarnings("unchecked")
1615
public LedSubsystem(Led led) {
1716
System.out.println("[LedSubsystem] Constructing LedSubsystem...");
1817
led.setStaticColor(Color.kAliceBlue);

src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,8 @@
3030
import edu.wpi.first.math.geometry.Rotation2d;
3131
import edu.wpi.first.wpilibj.AnalogInput;
3232
import edu.wpi.first.wpilibj.RobotController;
33+
import frc.robot.util.BrakeController;
34+
3335
import java.util.Queue;
3436
import java.util.function.DoubleSupplier;
3537

@@ -169,6 +171,8 @@ public ModuleIOSpark(int module) {
169171
() -> turnEncoder.setPosition(
170172
(turnAbsEncoder.getAverageVoltage() / RobotController.getVoltage5V())
171173
* 2 * Math.PI)); // If
174+
BrakeController.register(driveSpark); // # need test
175+
BrakeController.register(turnSpark); // # need test dont use before the test
172176
// inverted
173177
// is
174178
// true,
Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
package frc.robot.util;
2+
3+
import java.util.ArrayList;
4+
import java.util.List;
5+
6+
import com.revrobotics.spark.SparkBase;
7+
import com.revrobotics.spark.SparkBaseExtensions;
8+
9+
public final class BrakeController {
10+
11+
private static final List<SparkBase> motors = new ArrayList<>();
12+
13+
private BrakeController() {}
14+
15+
public static void register(SparkBase motor) {
16+
motors.add(motor);
17+
}
18+
19+
public static void setAllBrake(boolean brake) {
20+
for (SparkBase motor : motors) {
21+
SparkBaseExtensions.setBrakeMode(motor, brake);
22+
}
23+
}
24+
}

0 commit comments

Comments
 (0)