Skip to content

Commit

Permalink
Merge branch 'intake'
Browse files Browse the repository at this point in the history
  • Loading branch information
amrikverma committed Feb 2, 2024
2 parents 8d1fa85 + 6fc5701 commit c67672f
Show file tree
Hide file tree
Showing 3 changed files with 70 additions and 10 deletions.
5 changes: 5 additions & 0 deletions Robot2024/lib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,11 @@ plugins {
id 'maven-publish'
}

java {
sourceCompatibility = JavaVersion.VERSION_17
targetCompatibility = JavaVersion.VERSION_17
}

tasks.withType(JavaCompile) {
// Configure string concat to always inline compile
options.compilerArgs.add '-XDstringConcat=inline'
Expand Down
20 changes: 10 additions & 10 deletions Robot2024/src/main/java/com/team2813/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,20 +43,20 @@ public static class DriverConstants {
// back left swerve module
public static final int BACK_LEFT_DRIVE_ID = 10;
public static final int BACK_LEFT_ENCODER_ID = 11;
public static final int BACK_LEFT_STEER_ID = 12;
public static final int BACK_LEFT_STEER_ID = 12;

// pigeon
// pigeon
public static final int PIGEON_ID = 13;

//Mechanism CAN IDs
public static final int INTAKE = 14;
public static final int KICKER = 15;
public static final int SHOOTER_1 = 16;
//Mechanism CAN IDs
public static final int INTAKE = 14;
public static final int KICKER = 15;
public static final int SHOOTER_1 = 16;
public static final int SHOOTER_2 = 17;
public static final int SHOOTER_PIVOT= 18;
public static final int SHOOTER_ENCODER = 19;
public static final int CLIMBER = 20;
public static final int MAGAZINE = 21;
public static final int SHOOTER_PIVOT= 18;
public static final int SHOOTER_ENCODER = 19;
public static final int CLIMBER = 20;
public static final int MAGAZINE = 21;
public static final int INTAKE_ENCODER = 22;
public static final int INTAKE_PIVOT = 23;
}
55 changes: 55 additions & 0 deletions Robot2024/src/main/java/com/team2813/subsystems/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
package com.team2813.subsystems;

import com.ctre.phoenix.motorcontrol.TalonFXInvertType;
import com.ctre.phoenix.sensors.CANCoder;
import com.revrobotics.CANSparkLowLevel;

import com.team2813.lib2813.control.motors.TalonFXWrapper;
import com.team2813.lib2813.control.motors.SparkMaxWrapper;
import com.team2813.lib2813.control.ControlMode;
import com.team2813.lib2813.util.ConfigUtils;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import static com.team2813.Constants.*;
public class Intake extends SubsystemBase {
private final TalonFXWrapper intakeMotor = new TalonFXWrapper(INTAKE, TalonFXInvertType.CounterClockwise);
private final TalonFXWrapper pivotMotor = new TalonFXWrapper(INTAKE_PIVOT, TalonFXInvertType.CounterClockwise);
private final CANCoder encoder = new CANCoder(INTAKE_ENCODER);

//private final SparkMaxWrapper intakeMotor = new SparkMaxWrapper(INTAKE, CANSparkLowLevel.MotorType.kBrushless, true);
//private final SparkMaxWrapper pivotMotor = new SparkMaxWrapper(INTAKE_PIVOT, CANSparkLowLevel.MotorType.kBrushless, true);

private static final double INTAKE_SPEED = 0.25;
private static final double OUTTAKE_SPEED = -0.25;

private static final double PIVOT_UP_SPEED = .10;
private static final double PIVOT_DOWN_SPEED = -.10;


public Intake() {
//encoder.configSensorDirection(true);
}

public void intake() { intakeMotor.set(ControlMode.DUTY_CYCLE, INTAKE_SPEED); }

public void outtake() { intakeMotor.set(ControlMode.DUTY_CYCLE, OUTTAKE_SPEED); }

public void stopIntakeMotor() { intakeMotor.set(ControlMode.DUTY_CYCLE, 0); }

public void pivotUp() { pivotMotor.set(ControlMode.DUTY_CYCLE, PIVOT_UP_SPEED); }

public void pivotDown() { pivotMotor.set(ControlMode.DUTY_CYCLE, PIVOT_DOWN_SPEED); }

public void stopPivotMotor() { pivotMotor.set(ControlMode.DUTY_CYCLE, 0); }

public double getMeasurement() { return encoder.getPosition(); }

public void zeroSensors() { ConfigUtils.ctreConfig(() -> encoder.setPosition(0)); }



}


0 comments on commit c67672f

Please sign in to comment.