-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathRobotMap.java
More file actions
122 lines (95 loc) · 5.4 KB
/
RobotMap.java
File metadata and controls
122 lines (95 loc) · 5.4 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
package frc.robot;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.DigitalInput; // Add this import
import com.studica.frc.AHRS;
import com.studica.frc.AHRS.NavXComType;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.PneumaticHub;
import edu.wpi.first.wpilibj.Compressor;
public class RobotMap {
private class CAN {
// IMPORTANT: Make sure to update the CAN IDs to match the physical configuration of the robot
/* DRIVETRAIN */
private static final int LEFT_FRONT_DRIVE_CAN = 5;
private static final int LEFT_FRONT_ROTATE_CAN = 6;
private static final int RIGHT_FRONT_DRIVE_CAN = 1;
private static final int RIGHT_FRONT_ROTATE_CAN = 2;
private static final int LEFT_BACK_DRIVE_CAN = 7;
private static final int LEFT_BACK_ROTATE_CAN = 8;
private static final int RIGHT_BACK_DRIVE_CAN = 3;
private static final int RIGHT_BACK_ROTATE_CAN = 4;
private static final int ELEVATOR_MOTOR_LEADER_CAN = 10; // Leader elevator motor
private static final int ELEVATOR_MOTOR_FOLLOWER_CAN = 9; // Follower elevator motor
/* PNEUMATICS */
private static final int PCM_CAN_ID = 27; // Updated PCM ID (moved from 10)
/* MECHANISMS */
private static final int CORAL_CLAW_MOTOR_PRIMARY_CAN = 11; // First coral claw motor
private static final int CORAL_CLAW_MOTOR_SECONDARY_CAN = 12; // Second coral claw motor
/**
* FRONT
* |---------|
* |5,6 1,2|
* | |
* |7,8 3,4|
* |---------|
* BACK
**/
//Todo: verify that this is the order of the motors after the swerve drive is assembled
}
// IMPORTANT: Make sure to update the Analog IDs to match the physical configuration of the robot
private class Analog {
// Drivetrain
// This also uses all 4 available ports
private static final int LEFT_FRONT_ENCODER = 2;
private static final int RIGHT_FRONT_ENCODER = 0;
private static final int LEFT_BACK_ENCODER = 3;
private static final int RIGHT_BACK_ENCODER = 1;
}
// Digital I/O port configuration
private class DIO {
private static final int CORAL_LIMIT_SWITCH = 0; // Digital I/O port for coral limit switch
}
// Pneumatic port configuration
private class Pneumatics {
private static final int WRIST_FORWARD_CHANNEL = 0;
private static final int WRIST_REVERSE_CHANNEL = 1;
}
public static final TalonFX leftBackDrive = new TalonFX(CAN.LEFT_BACK_DRIVE_CAN);
public static final SparkMax leftBackRotate = new SparkMax(CAN.LEFT_BACK_ROTATE_CAN, MotorType.kBrushless);
public static final AnalogInput leftBackEncoder = new AnalogInput(Analog.LEFT_BACK_ENCODER);
public static final TalonFX rightBackDrive = new TalonFX(CAN.RIGHT_BACK_DRIVE_CAN);
public static final SparkMax rightBackRotate = new SparkMax(CAN.RIGHT_BACK_ROTATE_CAN, MotorType.kBrushless);
public static final AnalogInput rightBackEncoder = new AnalogInput(Analog.RIGHT_BACK_ENCODER);
public static final TalonFX leftFrontDrive = new TalonFX(CAN.LEFT_FRONT_DRIVE_CAN);
public static final SparkMax leftFrontRotate = new SparkMax(CAN.LEFT_FRONT_ROTATE_CAN, MotorType.kBrushless);
public static final AnalogInput leftFrontEncoder = new AnalogInput(Analog.LEFT_FRONT_ENCODER);
public static final TalonFX rightFrontDrive = new TalonFX(CAN.RIGHT_FRONT_DRIVE_CAN);
public static final SparkMax rightFrontRotate = new SparkMax(CAN.RIGHT_FRONT_ROTATE_CAN, MotorType.kBrushless);
public static final AnalogInput rightFrontEncoder = new AnalogInput(Analog.RIGHT_FRONT_ENCODER);
// Replace TalonFX with two SparkMax controllers
public static final SparkMax elevatorMotorLeader = new SparkMax(CAN.ELEVATOR_MOTOR_LEADER_CAN, MotorType.kBrushless);
public static final SparkMax elevatorMotorFollower = new SparkMax(CAN.ELEVATOR_MOTOR_FOLLOWER_CAN, MotorType.kBrushless);
// Pneumatic components
public static final PneumaticHub pneumaticHub = new PneumaticHub(CAN.PCM_CAN_ID);
public static final Compressor compressor = new Compressor(CAN.PCM_CAN_ID, PneumaticsModuleType.REVPH);
public static final DoubleSolenoid wristSolenoid = new DoubleSolenoid(
CAN.PCM_CAN_ID,
PneumaticsModuleType.REVPH,
Pneumatics.WRIST_FORWARD_CHANNEL,
Pneumatics.WRIST_REVERSE_CHANNEL
);
// Create two NEO motors for the coral claw
public static final SparkMax coralClawPrimaryMotor = new SparkMax(CAN.CORAL_CLAW_MOTOR_PRIMARY_CAN, MotorType.kBrushless);
public static final SparkMax coralClawSecondaryMotor = new SparkMax(CAN.CORAL_CLAW_MOTOR_SECONDARY_CAN, MotorType.kBrushless);
// Coral claw limit switch
public static final DigitalInput coralLimitSwitch = new DigitalInput(DIO.CORAL_LIMIT_SWITCH);
// Remove the subsystem instances from here
// public static final Elevator elevator = new Elevator();
// public static final Wrist wrist = new Wrist(wristSolenoid);
// public static final CoralClaw coralClaw = new CoralClaw(coralClawMotor);
public static final AHRS gyro = new AHRS(NavXComType.kMXP_SPI);
}