Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 6 additions & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def deployArtifact = deploy.targets.roborio.artifacts.frcJava
wpi.java.debugJni = false

// Set this to true to enable desktop support.
def includeDesktopSupport = false
def includeDesktopSupport = true;

// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 5.
Expand Down Expand Up @@ -79,6 +79,11 @@ test {
wpi.sim.addGui().defaultEnabled = true
wpi.sim.addDriverstation()

//Sets the websocket client remote host.
wpi.sim.envVar("HALSIMWS_HOST", "10.0.0.2")
wpi.sim.addWebsocketsServer().defaultEnabled = true
wpi.sim.addWebsocketsClient().defaultEnabled = true

// Setting up my Jar File. In this case, adding all libraries into the main jar ('fat jar')
// in order to make them all available at runtime. Also adding the manifest so WPILib
// knows where to look for our Robot Class.
Expand Down
74 changes: 55 additions & 19 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,47 +10,80 @@
import com.revrobotics.CANSparkMaxLowLevel.MotorType;

import frc.robot.Constants;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.DifferentialDriveOdometry;

import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.romi.RomiGyro;

public class Drivetrain extends SubsystemBase {
/** Creates a new Drivetrain. */
CANSparkMax rightFrontSpark;
CANSparkMax rightBackSpark;
CANSparkMax leftFrontSpark;
CANSparkMax leftBackSpark;
MotorControllerGroup rightMotors;
MotorControllerGroup leftMotors;
DifferentialDrive dDrive;

CANSparkMax rightFrontSpark;
CANSparkMax rightBackSpark;
CANSparkMax leftFrontSpark;
CANSparkMax leftBackSpark;
MotorControllerGroup rightMotors;
MotorControllerGroup leftMotors;
DifferentialDrive dDrive;
DifferentialDriveOdometry m_odometry;
Pose2d m_pose;

private Spark rightMotorRomi;
private Spark leftMotorRomi;
private Encoder leftEncoderRomi;
private Encoder rightEncoderRomi;
private RomiGyro gyroRomi;


public Drivetrain() {
rightFrontSpark = new CANSparkMax(Constants.RIGHT_FRONT_SPARK, MotorType.kBrushless);
rightBackSpark = new CANSparkMax(Constants.RIGHT_BACK_SPARK, MotorType.kBrushless);
leftFrontSpark = new CANSparkMax(Constants.LEFT_FRONT_SPARK, MotorType.kBrushless);
leftBackSpark = new CANSparkMax(Constants.LEFT_BACK_SPARK, MotorType.kBrushless);
if (RobotBase.isReal()) {
rightFrontSpark = new CANSparkMax(Constants.RIGHT_FRONT_SPARK, MotorType.kBrushless);
rightBackSpark = new CANSparkMax(Constants.RIGHT_BACK_SPARK, MotorType.kBrushless);
leftFrontSpark = new CANSparkMax(Constants.LEFT_FRONT_SPARK, MotorType.kBrushless);
leftBackSpark = new CANSparkMax(Constants.LEFT_BACK_SPARK, MotorType.kBrushless);

rightBackSpark.follow(rightFrontSpark);
leftBackSpark.follow(leftFrontSpark);

//rightBackSpark.follow(rightFrontSpark);
//leftBackSpark.follow(leftFrontSpark);

rightFrontSpark.enableVoltageCompensation(12);
rightBackSpark.enableVoltageCompensation(12);
leftFrontSpark.enableVoltageCompensation(12);
leftBackSpark.enableVoltageCompensation(12);
rightFrontSpark.setIdleMode(IdleMode.kBrake);
rightBackSpark.setIdleMode(IdleMode.kBrake);
leftFrontSpark.setIdleMode(IdleMode.kBrake);
leftBackSpark.setIdleMode(IdleMode.kBrake);

rightFrontSpark.setIdleMode(IdleMode.kCoast);
rightBackSpark.setIdleMode(IdleMode.kCoast);
leftFrontSpark.setIdleMode(IdleMode.kCoast);
leftBackSpark.setIdleMode(IdleMode.kCoast);

} else {
// PWM channels 0 and 1 respectively
leftMotorRomi = new Spark(0);
rightMotorRomi = new Spark(1);

rightMotors = new MotorControllerGroup(rightMotorRomi);
leftMotors = new MotorControllerGroup(leftMotorRomi);
leftEncoderRomi = new Encoder(4, 5);
rightEncoderRomi = new Encoder(6, 7);

gyroRomi = new RomiGyro();

}

rightMotors = new MotorControllerGroup(rightFrontSpark, rightBackSpark);
leftMotors = new MotorControllerGroup(leftFrontSpark, leftBackSpark);
dDrive = new DifferentialDrive(leftMotors, rightMotors);
//m_odometry = new DifferentialDriveOdometry(
// gyroSim.getRotation2d(),
// leftEncoderSim.getDistance(), rightEncoderSim.getDistance());


}

public void arcadeDrive(double speed, double rotation){

dDrive.arcadeDrive(speed, rotation);
Expand All @@ -69,5 +102,8 @@ public void tankDrive(double right, double left){
@Override
public void periodic() {
// This method will be called once per scheduler run
//m_pose = m_odometry.update(gyroSim.getRotation2d(),
// leftEncoderSim.getDistance(),
// rightEncoderSim.getDistance());
}
}
36 changes: 36 additions & 0 deletions vendordeps/RomiVendordep.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
{
"fileName": "RomiVendordep.json",
"name": "Romi-Vendordep",
"version": "2022.2.1",
"uuid": "2854af28-a682-4c3e-abe5-1f62c288c6b8",
"mavenUrls": [],
"jsonUrl": "",
"javaDependencies": [
{
"groupId": "edu.wpi.first.romi",
"artifactId": "romi-vendordep-java",
"version": "2022.2.1"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "edu.wpi.first.romi",
"artifactId": "romi-vendordep-cpp",
"version": "2022.2.1",
"libName": "romiVendordep",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"linuxraspbian",
"linuxaarch64bionic",
"windowsx86-64",
"windowsx86",
"linuxx86-64",
"osxx86-64"
]
}
]
}