-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathRobotContainer.java
157 lines (114 loc) · 4.99 KB
/
RobotContainer.java
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
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.armCommand.dpad;
import frc.robot.commands.climberCommand.climberCom;
import frc.robot.commands.intakeCommand.Intake;
import frc.robot.commands.intakeCommand.expel;
import frc.robot.commands.intakeCommand.outtake;
import frc.robot.subsystems.ArmSubsystem;
import frc.robot.subsystems.IntakeSubsystem.IntakeSubsystem;
import frc.robot.subsystems.IntakeSubsystem.ShooterSubsystem;
import frc.robot.subsystems.swervedrive.SwerveSubsystem;
import java.io.File;
import com.pathplanner.lib.auto.NamedCommands;
/**
* This class is where the bulk of the robot should be declared. Since Command-based is a "declarative" paradigm, very
* littobot logic should actually be handled in the {@link Robot} periodic methods (other than the scheduler calls).
* Instead, the structure of the robot (including subsystems, commands, and trigger mappings) should be declared here.
*/
public class RobotContainer
{
// The robot's subsystems and commands are defined here...
private final SwerveSubsystem drivebase;
// Replace with CommandPS4Controller or CommandJoystick if needed
final CommandXboxController armPS5 = new CommandXboxController(0);
private final frc.robot.subsystems.IntakeSubsystem.IntakeSubsystem Intake ;
private final ShooterSubsystem shooter ;
private final ArmSubsystem Arm;
private final Intake intakecom;
private final outtake outtake;
private final dpad dpadComUp;
private final dpad dpadComdown ;
private final climberCom climberComUp ;
private final climberCom climberComDown ;
private final expel expeliat ;
/**
* The container for the robot. Contains subsystems, OI devices, and commands.
*/
public RobotContainer()
{
shooter = new ShooterSubsystem();
drivebase = new SwerveSubsystem(new File(Filesystem.getDeployDirectory(),
"swerve"));
Intake = new IntakeSubsystem();
Arm = new ArmSubsystem(9, 10, 11, 12);
intakecom= new Intake(Intake);
outtake = new outtake(Intake);
dpadComUp = new dpad(Arm, 1);
dpadComdown = new dpad(Arm, -1);
climberComUp = new climberCom(Arm, 1);
climberComDown = new climberCom(Arm, -1);
expeliat = new expel(shooter);
NamedCommands.registerCommand("shoot", expeliat);
NamedCommands.registerCommand("intake", intakecom);
NamedCommands.registerCommand("outtake", outtake);
NamedCommands.registerCommand("arm down", dpadComdown);
NamedCommands.registerCommand("arm up", dpadComUp);
NamedCommands.registerCommand("", climberComDown);
NamedCommands.registerCommand("", climberComDown);
// Configure the trigger bindings
configureBindings();
// Applies deadbands and inverts controls because joysticks
// are back-right positive while robot
// controls are front-left positive
// left stick controls translation
// right stick controls the angular velocity of the robot
Command driveFieldOrientedAnglularVelocity = drivebase.driveCommand(
() -> MathUtil.applyDeadband(armPS5.getLeftY(), 0.025),
() -> MathUtil.applyDeadband(armPS5.getLeftX(), 0.025),
() -> MathUtil.applyDeadband(armPS5.getRightX(), 0.2));
drivebase.setDefaultCommand( driveFieldOrientedAnglularVelocity);
}
/**
* Use this method to define your trigger->command mappings. Triggers can be created via the
* {@link Trigger#Trigger(java.util.function.BooleanSupplier)} constructor with an arbitrary predicate, or via the
* named factories in {@link edu.wpi.first.wpilibj2.command.button.CommandGenericHID}'s subclasses for
* {@link CommandXboxController Xbox}/{@link edu.wpi.first.wpilibj2.command.button.CommandPS4Controller PS4}
* controllers or {@link edu.wpi.first.wpilibj2.command.button.CommandJoystick Flight joysticks}.
*/
private void configureBindings()
{
armPS5.povUp().whileTrue(dpadComUp);
armPS5.povDown().whileTrue(dpadComdown);
armPS5.a().whileTrue(intakecom);
armPS5.x().whileTrue(outtake);
armPS5.b().toggleOnTrue(expeliat);
armPS5.leftBumper().whileTrue(climberComUp);
armPS5.rightBumper().whileTrue(climberComDown);
}
/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
*/
public Command getAutonomousCommand()
{
// An example command will be run in autonomous
return drivebase.getAutonomousCommand("New Auto");
}
public void setDriveMode()
{
//drivebase.setDefaultCommand();
}
public void setMotorBrake(boolean brake)
{
drivebase.setMotorBrake(false);
}
}