Skip to content

Commit

Permalink
Merge pull request #59 from sonic-howl/develop
Browse files Browse the repository at this point in the history
Test
  • Loading branch information
Portnord authored May 28, 2024
2 parents 725a29f + efc50ab commit 19e9d02
Show file tree
Hide file tree
Showing 8 changed files with 362 additions and 73 deletions.
152 changes: 132 additions & 20 deletions boards/swerveboard.json
Original file line number Diff line number Diff line change
Expand Up @@ -11,22 +11,6 @@
"vgap": 16.0,
"titleType": 0,
"tiles": {
"0,0": {
"size": [
16,
8
],
"content": {
"_type": "Field",
"_source0": "network_table:///SmartDashboard/Field",
"_title": "Field",
"_glyph": 148,
"_showGlyph": false,
"Game/Game": "k2024Crescendo",
"Visuals/Robot Icon Size": 50.0,
"Visuals/Show Outside Circles": false
}
},
"16,0": {
"size": [
1,
Expand Down Expand Up @@ -363,6 +347,48 @@
"_glyph": 148,
"_showGlyph": false
}
},
"0,0": {
"size": [
1,
1
],
"content": {
"_type": "ComboBox Chooser",
"_source0": "network_table:///SmartDashboard/Auto choices",
"_title": "Auto choices",
"_glyph": 148,
"_showGlyph": false
}
},
"1,0": {
"size": [
8,
5
],
"content": {
"_type": "Field",
"_source0": "network_table:///SmartDashboard/Field",
"_title": "Field",
"_glyph": 148,
"_showGlyph": false,
"Game/Game": "k2024Crescendo",
"Visuals/Robot Icon Size": 50.0,
"Visuals/Show Outside Circles": false
}
},
"9,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/fieldOriented",
"_title": "fieldOriented",
"_glyph": 148,
"_showGlyph": false
}
}
}
}
Expand Down Expand Up @@ -580,12 +606,98 @@
}
}
}
},
{
"title": "Odometry",
"autoPopulate": false,
"autoPopulatePrefix": "",
"widgetPane": {
"gridSize": 128.0,
"showGrid": true,
"hgap": 16.0,
"vgap": 16.0,
"titleType": 0,
"tiles": {
"0,0": {
"size": [
2,
2
],
"content": {
"_type": "Gyro",
"_source0": "network_table:///Pose Table/Odometry R",
"_title": "Pose Table/Odometry R",
"_glyph": 148,
"_showGlyph": false,
"Visuals/Major tick spacing": 45.0,
"Visuals/Starting angle": 90.0,
"Visuals/Show tick mark ring": true,
"Visuals/Counter clockwise": true
}
},
"0,2": {
"size": [
4,
1
],
"content": {
"_type": "Number Bar",
"_source0": "network_table:///Pose Table/Odometry X",
"_title": "Pose Table/Odometry X",
"_glyph": 148,
"_showGlyph": false,
"Range/Min": 0.0,
"Range/Max": 16.0,
"Range/Center": 0.0,
"Visuals/Num tick marks": 5,
"Visuals/Show text": true,
"Visuals/Orientation": "HORIZONTAL"
}
},
"4,0": {
"size": [
1,
3
],
"content": {
"_type": "Number Bar",
"_source0": "network_table:///Pose Table/Odometry Y",
"_title": "Pose Table/Odometry Y",
"_glyph": 148,
"_showGlyph": false,
"Range/Min": 0.0,
"Range/Max": 10.0,
"Range/Center": 0.0,
"Visuals/Num tick marks": 5,
"Visuals/Show text": true,
"Visuals/Orientation": "VERTICAL"
}
},
"2,0": {
"size": [
2,
2
],
"content": {
"_type": "Gyro",
"_source0": "network_table:///Pose Table/Gyro Angle",
"_title": "Pose Table/Gyro Angle",
"_glyph": 148,
"_showGlyph": false,
"Visuals/Major tick spacing": 45.0,
"Visuals/Starting angle": 180.0,
"Visuals/Show tick mark ring": true,
"Visuals/Counter clockwise": false
}
}
}
}
}
],
"windowGeometry": {
"x": -8.0,
"y": -8.0,
"width": 2576.0,
"height": 1568.0
"x": 0.800000011920929,
"y": 0.800000011920929,
"width": 1534.4000244140625,
"height": 910.4000244140625
}
}
36 changes: 36 additions & 0 deletions src/constants/FieldConstants.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
import math

from wpimath.geometry import Pose2d, Translation2d

from constants.RobotConstants import RobotConstants

MetersPerInch = 0.0254

kSpeakerShootingRange = (72 + (RobotConstants.frame_length / 2)) * MetersPerInch
kAmpShootingRange = (
0 + (RobotConstants.frame_length / 2 + RobotConstants.bumper_width)
) * MetersPerInch
kPickupRange = (20 + (RobotConstants.frame_length / 2)) * MetersPerInch
## Locations -- https://firstfrc.blob.core.windows.net/frc2024/FieldAssets/2024LayoutMarkingDiagram.pdf, page 4 ##

# Speaker locations #
kBlueSpeakerLocation = Pose2d(0, 218.42 * MetersPerInch, math.pi)
kRedSpeakerLocation = Pose2d(652.77 * MetersPerInch, 216.32 * MetersPerInch, 0)
# Amp locations #
kBlueAmpLocation = Pose2d(72.5 * MetersPerInch, 323 * MetersPerInch, math.pi / 2)
kRedAmpLocation = Pose2d(578.757 * MetersPerInch, 323 * MetersPerInch, math.pi / 2)
# Pickup locations (Scoring table perspective) #
kBluePickupLeftLocation = Pose2d(
14.02 * MetersPerInch, 34.79 * MetersPerInch, math.pi / 3
)
kBluePickupRightLocation = Pose2d(
57.54 * MetersPerInch, 9.68 * MetersPerInch, math.pi / 3
)
kRedPickupLeftLocation = Pose2d(
593.68 * MetersPerInch, 9.68 * MetersPerInch, math.pi * 2 / 3
)
kRedPickupRightLocation = Pose2d(
637.21 * MetersPerInch, 34.79 * MetersPerInch, math.pi * 2 / 3
)
BluePickupOffset = Translation2d(kPickupRange, math.pi / 3)
RedPickupOffset = Translation2d(kPickupRange, math.pi * 2 / 3)
26 changes: 20 additions & 6 deletions src/driveteam.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ def __init__(self):
self.pilot = wpilib.XboxController(0)
self.copilot = wpilib.XboxController(1)

### Pilot ###
def get_strafe_command(self):
return -self.pilot.getLeftX()

Expand All @@ -30,6 +31,25 @@ def get_hook_left_command(self):
def get_hook_right_command(self):
return self.pilot.getPOV() == 180

def get_view_command(self) -> bool: # swap between 3rd & first person view
return self.pilot.getBackButtonPressed()

def get_move_to_amp_command(self):
# return self.pilot.getYButton()
return False

def get_move_to_speaker_command(self):
return self.pilot.getAButton()

def get_move_to_pickup_left_command(self):
# return self.pilot.getXButton()
return False

def get_move_to_pickup_right_command(self):
# return self.pilot.getBButton()
return False

### Copilot ###
def get_aim_command(self) -> float: # raise/lower shooter
return self.copilot.getLeftY()

Expand All @@ -45,11 +65,5 @@ def get_pickup_command(self) -> float: # used to pickup rings
def get_eject_command(self) -> bool: # eject stuck note
return self.copilot.getLeftBumper()

def get_test_command(self):
return self.pilot.getAButton()

def get_test_command2(self):
return self.copilot.getAButton()

def get_view_command(self) -> bool: # swap between 3rd & first person view
return self.pilot.getBackButtonPressed()
31 changes: 16 additions & 15 deletions src/launcher.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@ def __init__(self):

self.feed = rev.CANSparkMax(12, rev.CANSparkLowLevel.MotorType.kBrushless)

if wpilib.RobotBase.isReal():
self.elevator = rev.CANSparkMax(13, rev.CANSparkLowLevel.MotorType.kBrushed)
else:
self.elevator = rev.CANSparkMax(13, rev.CANSparkLowLevel.MotorType.kBrushless)
# if wpilib.RobotBase.isReal():
# self.elevator = rev.CANSparkMax(13, rev.CANSparkLowLevel.MotorType.kBrushed)
# else:
# self.elevator = rev.CANSparkMax(13, rev.CANSparkLowLevel.MotorType.kBrushless)

# Limit switches
self.upperswitch = wpilib.DigitalInput(1)
Expand All @@ -24,10 +24,11 @@ def __init__(self):
self.firetimer = 75

def stop(self):
# self.motor1.set(0.0)
# self.motor2.set(0.0)
self.motor1.set(0.0)
self.motor2.set(0.0)

self.feed.set(0.0)
self.elevator.set(0.0)
# self.elevator.set(0.0)
self.firetimer = 75 # In robot cycles

def shoot(self, fire: float):
Expand All @@ -37,8 +38,8 @@ def shoot(self, fire: float):
# Stop unrelated motors
# self.elevator.set(0.0)
# Spool up rollers
# self.motor1.set(-fire)
# self.motor2.set(fire)
self.motor1.set(-fire)
self.motor2.set(fire)
self.firetimer = self.firetimer - 1

# Feed ring into launcher when we are at the lowered position
Expand All @@ -52,8 +53,8 @@ def unjams(self):
# Stop unrelated motors
# self.elevator.set(0.0)
# Reverse rollers
# self.motor1.set(0.25)
# self.motor2.set(-0.25)
self.motor1.set(0.25)
self.motor2.set(-0.25)
self.feed.set(-0.5)

### Elevator is currently not physically implemented. Might be added later. ###
Expand Down Expand Up @@ -101,8 +102,8 @@ def unjams(self):

def pickup(self):
# # Stop unrelated motors
# self.motor1.set(0.0)
# self.motor2.set(0.0)
self.motor1.set(0.0)
self.motor2.set(0.0)
# self.elevator.set(0.0)
# Stop when note reaches limit switch in the feed mechanism
if not self.feedswitch.get():
Expand All @@ -113,8 +114,8 @@ def pickup(self):

def eject(self):
# Stop unrelated motors
# self.motor1.set(0.0)
# self.motor2.set(0.0)
self.motor1.set(0.0)
self.motor2.set(0.0)
# self.elevator.set(0.0)
# Push note back out the pickup
self.feed.set(-0.5)
4 changes: 2 additions & 2 deletions src/pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
[tool.robotpy]

# Version of robotpy this project depends on
robotpy_version = "2024.3.1.0"
robotpy_version = "2024.3.2.1"

# Which extra RobotPy components should be installed
# -> equivalent to `pip install robotpy[extra1, ...]
Expand Down Expand Up @@ -93,4 +93,4 @@ indent-style = "space"
# Respect magic trailing commas.
skip-magic-trailing-comma = false
# Automatically detect the appropriate line ending.
line-ending = "auto"
line-ending = "auto"
Loading

0 comments on commit 19e9d02

Please sign in to comment.