-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathrobot.py
More file actions
executable file
·126 lines (91 loc) · 3.76 KB
/
robot.py
File metadata and controls
executable file
·126 lines (91 loc) · 3.76 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
123
124
125
126
#!/usr/bin/env python3
'''
Blue Crew Robot Code for FIRST Power Up
Codename: Kylo
'''
import wpilib
import wpilib.drive
import threading
from wpilib.buttons import JoystickButton
from magicbot import MagicRobot
from robotpy_ext.common_drivers import navx
from components.DriveTrain import DriveTrain
from components.CubeMech import CubeMech
from components.RampMech import RampMech
from common.driveControls import driveControls
from common.armMech import armMech
from common.shootMech import shootMech
from common.subsystemAux import subsystemAux
from common.driveAux import driveAux
from common.xbox import XboxController
class Kylo(MagicRobot):
# Initialize Robot Components
drivetrain = DriveTrain
cubemech = CubeMech
rampmech = RampMech
def createObjects(self):
# Define Driving Motors
self.rightDrive = wpilib.VictorSP(0)
self.leftDrive = wpilib.VictorSP(1)
# Create Robot Drive
self.robotDrive = wpilib.drive.DifferentialDrive(self.rightDrive, self.leftDrive)
# Create Shifter Pneumatics
self.shifterSolenoid = wpilib.DoubleSolenoid(0, 0, 1)
# Joysticks and Controllers
self.driveJoystick = wpilib.Joystick(0)
self.driveController = XboxController(0)
self.subsystemJoystick = wpilib.Joystick(1)
self.subsystemController = XboxController(1)
# Create NavX and Accel
self.navX = navx.AHRS.create_spi()
self.accel = wpilib.BuiltInAccelerometer()
# Set Drivespeed
self.driveSpeed = 0
# Intake Motors
self.intakeMotor = wpilib.VictorSP(2)
# Intake Lifter
self.intakeLifter = wpilib.Spark(6)
# Create Cube Intake Pneumatics
self.intakeSolenoid = wpilib.Solenoid(0, 2)
# Create Ramp Motors
self.rightRamp = wpilib.Spark(5)
self.leftRamp = wpilib.Spark(4)
# Create Ramp Deploy Pneumatics
self.rampSolenoid = wpilib.Solenoid(0, 3)
# Create Timer (For Making Timed Events)
self.timer = wpilib.Timer()
# Initialize Compressor
self.compressor = wpilib.Compressor()
# Create CameraServer
wpilib.CameraServer.launch("common/multipleCameras.py:main")
# Set Gear in Dashboard
wpilib.SmartDashboard.putString("Shift State", "Low Gear")
wpilib.SmartDashboard.putString("Cube State", "Unclamped")
def teleopInit(self):
# Init Drive Controls
DriverController = driveControls("DriveController", self.driveController, self.drivetrain, self.cubemech, self.rampmech, self.driveJoystick, .05)
DriveAux = driveAux("DriveAux", self.driveController, self.drivetrain, self.cubemech, self.rampmech, self.driveJoystick, .05)
# Init Subsystem Controls
ArmMech = armMech("ArmMech", self.subsystemController, self.driveJoystick, self.cubemech, self.rampmech, .1)
ShootMech = shootMech("ShootMech", self.subsystemController, self.driveJoystick, self.cubemech, self.rampmech, .1)
SubsystemAux = subsystemAux("SubsystemAux", self.subsystemController, self.driveJoystick, self.cubemech, self.rampmech, .1)
# Start Drive Controls
DriveAux.start()
DriverController.start()
# Start Subsystem Controls
ArmMech.start()
ShootMech.start()
SubsystemAux.start()
# Start and Reset Timer
self.timer.reset()
self.timer.start()
def teleopPeriodic(self):
# Pressurize Throughout Teleop
self.compressor.start()
# Rumble Controller
if (self.timer.get() > 75 and self.timer.get() < 105):
self.driveController.rumble(1, 1)
else:
self.driveController.rumble(0, 0)
if __name__ == '__main__':
wpilib.run(Kylo)