forked from thedropbears/pyinfiniterecharge
-
Notifications
You must be signed in to change notification settings - Fork 0
/
robot.py
executable file
·206 lines (166 loc) · 7.29 KB
/
robot.py
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
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
#!/usr/bin/env python3
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
# Open Source Software - may be modified and shared by FRC teams. The code
# must be accompanied by the FIRST BSD license file in the root directory of
# the project.
import math
import ctre
import magicbot
import rev.color
import wpilib
from components.chassis import Chassis
from components.hang import Hang
from components.indexer import Indexer
from components.shooter import Shooter
from components.spinner import Spinner
from components.range_finder import RangeFinder
from components.turret import Turret
from components.vision import Vision
from components.led_screen import LEDScreen
from controllers.shooter import ShooterController
from controllers.spinner import SpinnerController
from utilities import git
from utilities.nav_x import NavX
from utilities.scalers import rescale_js, scale_value
GIT_COMMIT = git.describe()
class MyRobot(magicbot.MagicRobot):
# List sensors which should collect data before controllers here.
vision: Vision
# List controllers (which require components) here.
shooter_controller: ShooterController
spinner_controller: SpinnerController
# List components (which represent physical subsystems) here.
chassis: Chassis
hang: Hang
range_finder: RangeFinder
indexer: Indexer
shooter: Shooter
spinner: Spinner
turret: Turret
led_screen: LEDScreen
def createObjects(self):
"""Robot initialization function"""
self.logger.info("pyinfiniterecharge %s", GIT_COMMIT)
self.chassis_left_front = rev.CANSparkMax(5, rev.MotorType.kBrushless)
self.chassis_left_rear = rev.CANSparkMax(4, rev.MotorType.kBrushless)
self.chassis_right_front = rev.CANSparkMax(7, rev.MotorType.kBrushless)
self.chassis_right_rear = rev.CANSparkMax(6, rev.MotorType.kBrushless)
self.imu = NavX()
self.hang_winch_motor = ctre.WPI_TalonFX(30)
self.hang_kracken_hook_latch = wpilib.DoubleSolenoid(4, 5)
self.indexer_motors = [
ctre.WPI_TalonSRX(18),
ctre.WPI_TalonSRX(11),
ctre.WPI_TalonSRX(12),
ctre.WPI_TalonSRX(13),
ctre.WPI_TalonSRX(14),
]
self.piston_switch = wpilib.DigitalInput(4) # checks if injector retracted
self.intake_arm_piston = wpilib.Solenoid(1)
self.intake_left_motor = rev.CANSparkMax(8, rev.MotorType.kBrushless)
self.intake_right_motor = rev.CANSparkMax(9, rev.MotorType.kBrushless)
self.led_screen_led = wpilib.AddressableLED(0)
self.loading_piston = wpilib.DoubleSolenoid(6, 7)
self.shooter_centre_motor = ctre.WPI_TalonFX(2)
self.shooter_outer_motor = ctre.WPI_TalonFX(3)
self.range_counter = wpilib.Counter(6)
self.colour_sensor = rev.color.ColorSensorV3(wpilib.I2C.Port.kOnboard)
self.spinner_motor = wpilib.Spark(2)
self.spinner_solenoid = wpilib.DoubleSolenoid(2, 3)
self.turret_centre_index = wpilib.DigitalInput(0)
self.turret_right_index = wpilib.DigitalInput(1)
self.turret_left_index = wpilib.DigitalInput(2)
self.turret_motor = ctre.WPI_TalonSRX(10)
# operator interface
self.driver_joystick = wpilib.Joystick(0)
self.MEMORY_CONSTANT = int(0.1 / self.control_loop_wait_time)
# how long before data times out
def autonomousInit(self) -> None:
"""Initialise things for all autonomous modes."""
self.chassis.enable_closed_loop()
self.indexer.shimmying = False
def disabledPeriodic(self) -> None:
self.vision.execute()
def teleopInit(self) -> None:
"""Initialise things for driver control."""
self.chassis.disable_closed_loop()
self.indexer.shimmying = True
def teleopPeriodic(self):
"""Executed every cycle"""
self.handle_intake_inputs(self.driver_joystick)
self.handle_chassis_inputs(self.driver_joystick)
self.handle_spinner_inputs(self.driver_joystick)
self.handle_shooter_inputs(self.driver_joystick)
self.handle_hang_inputs(self.driver_joystick)
self.shooter_controller.engage()
def handle_intake_inputs(self, joystick: wpilib.Joystick) -> None:
if joystick.getRawButtonPressed(6):
if self.indexer.intaking:
self.indexer.disable_intaking()
else:
self.indexer.enable_intaking()
def handle_spinner_inputs(self, joystick: wpilib.Joystick) -> None:
if joystick.getRawButtonPressed(7):
self.spinner_controller.run(test=True, task="position")
print(f"Spinner Running")
if joystick.getRawButtonPressed(9):
self.spinner.piston_up()
print("Spinner Piston Up")
if joystick.getRawButtonPressed(10):
self.spinner.piston_down()
print("Spinner Piston Down")
if joystick.getRawButtonPressed(8):
print(f"Detected Colour: {self.spinner_controller.get_current_colour()}")
print(f"Distance: {self.spinner_controller.get_wheel_dist()}")
def handle_chassis_inputs(self, joystick: wpilib.Joystick) -> None:
throttle = scale_value(joystick.getThrottle(), 1, -1, 0, 1)
vx = 3 * throttle * rescale_js(-joystick.getY(), 0.1)
vz = 3 * throttle * rescale_js(-joystick.getTwist(), 0.1)
self.chassis.drive(vx, vz)
def handle_shooter_inputs(self, joystick: wpilib.Joystick) -> None:
if joystick.getTrigger():
self.shooter_controller.fire_input()
def handle_hang_inputs(self, joystick: wpilib.Joystick) -> None:
if joystick.getRawButton(3) and joystick.getRawButton(4):
self.hang.raise_hook()
if self.hang.fire_hook and joystick.getRawButton(4):
self.hang.winch()
def testInit(self):
self.turret.index_found = False
self.turret.on_enable()
def testPeriodic(self):
self.vision.execute()
self.shooter.execute()
if self.driver_joystick.getRawButtonPressed(10):
self.shooter.fire()
self.indexer.enable_intaking()
# Slew the turret
slew_increment = math.radians(5) # radians
if self.driver_joystick.getRawButtonPressed(6):
self.turret.slew(-slew_increment)
self.turret.execute()
elif self.driver_joystick.getRawButtonPressed(5):
self.turret.slew(slew_increment)
self.turret.execute()
# Pay out the winch after a match
if self.driver_joystick.getRawButton(4):
self.hang.pay_out()
self.hang.execute()
if self.driver_joystick.getTrigger():
self.indexer.enable_intaking()
if self.driver_joystick.getRawButtonPressed(7):
self.indexer.shimmy_speed += 0.1
if self.indexer.shimmy_speed > 1:
self.indexer.shimmy_speed = 1
self.indexer.left = True
if self.driver_joystick.getRawButtonPressed(9):
self.indexer.shimmy_speed -= 0.1
if self.indexer.shimmy_speed < 0:
self.indexer.shimmy_speed = 0
if self.indexer.intaking:
self.indexer.intake_motor_speed = (
self.driver_joystick.getThrottle() + 1
) / 2
self.indexer.execute()
if __name__ == "__main__":
wpilib.run(MyRobot)