Skip to content
This repository has been archived by the owner on Jan 10, 2025. It is now read-only.

Commit

Permalink
Merge pull request #7 from FRC-1721/pivot/commands_template
Browse files Browse the repository at this point in the history
Pivot/commands template
  • Loading branch information
Kredcool authored Jan 27, 2024
2 parents b20c2d3 + 23e9f75 commit 9b5326e
Show file tree
Hide file tree
Showing 23 changed files with 1,091 additions and 1,786 deletions.
6 changes: 6 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -165,3 +165,9 @@ cython_debug/

# Joe's not sure what this is for, put it back in the tree only if needed.
networktables.json

# Add to tree but only when neccicary (adding a map or smthn)
simgui-window.json

# sysid ignores
*.SysId
19 changes: 9 additions & 10 deletions rio/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -13,22 +13,21 @@ help: ## Prints this help message
sim: ## Run the simulator
python -m robotpy sim


deploy: ## Deploy to the robot (with console)
deploy: ## Deploy to the robot (with netconsole)
python -m robotpy deploy --nc


push: ## Deploy to the robot (push only, no console)
push: ## Deploy to the robot (push only, no netconsole)
python -m robotpy deploy


download: ## Download robot requirements locally
robotpy-installer download -r robot_requirements.txt

python -m robotpy installer download -r robot_requirements.txt
python -m robotpy installer download-python

install: ## Install requirements, run download first!
robotpy-installer install -r robot_requirements.txt
python -m robotpy installer install -r robot_requirements.txt

sync: ## Sync robotpy requirements
python -m robotpy sync

info: ## Shortcut to get information about the code already on the bot
python -m robotpy deploy-info
Expand All @@ -37,10 +36,10 @@ test: ## Run automated tests
python -m robotpy test

download-python: ## Download python (for robot)
robotpy-installer download-python
python -m robotpy installer download-python

install-python: ## Install python (for robot)
robotpy-installer install-python
python -m robotpy installer install-python

clean: ## Clean the repo
git clean -fdX
12 changes: 5 additions & 7 deletions rio/Pipfile
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,14 @@ verify_ssl = true
name = "pypi"

[packages]
robotpy = {extras = ["rev", "ctre", "commands2", "navx"]}
wpilib = {extras = ["all"]}
pyyaml = "6.0"
black = "*"
robotpy = "2024.2.1.1"
robotpy-rev = "2024.2.0"
robotpy-ctre = "2024.1.1"
robotpy-navx = "2024.1.0"
robotpy-commands-v2 = "2024.2.1"

[dev-packages]
black = "*"

[requires]
python_version = "3.11"

[pipenv]
allow_prereleases = true
1,353 changes: 248 additions & 1,105 deletions rio/Pipfile.lock

Large diffs are not rendered by default.

55 changes: 0 additions & 55 deletions rio/commands/FlyByWire.py

This file was deleted.

141 changes: 141 additions & 0 deletions rio/constants.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,141 @@
# 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.

"""
The constants module is a convenience place for teams to hold robot-wide
numerical or boolean constants. Don't use this for any other purpose!
"""


import math

from wpimath import units
from wpimath.geometry import Translation2d
from wpimath.kinematics import SwerveDrive4Kinematics
from wpimath.trajectory import TrapezoidProfileRadians

from rev import CANSparkMax


class NeoMotorConstants:
kFreeSpeedRpm = 5676


class DriveConstants:
# Driving Parameters - Note that these are not the maximum capable speeds of
# the robot, rather the allowed maximum speeds
kMaxSpeedMetersPerSecond = 4.8
kMaxAngularSpeed = math.tau # radians per second

kDirectionSlewRate = 1.2 # radians per second
kMagnitudeSlewRate = 1.8 # percent per second (1 = 100%)
kRotationalSlewRate = 2.0 # percent per second (1 = 100%)

# Chassis configuration
kTrackWidth = units.inchesToMeters(20.3937)
# Distance between centers of right and left wheels on robot
kWheelBase = units.inchesToMeters(20.25)

# Distance between front and back wheels on robot
kModulePositions = [
Translation2d(kWheelBase / 2, kTrackWidth / 2),
Translation2d(kWheelBase / 2, -kTrackWidth / 2),
Translation2d(-kWheelBase / 2, kTrackWidth / 2),
Translation2d(-kWheelBase / 2, -kTrackWidth / 2),
]
kDriveKinematics = SwerveDrive4Kinematics(*kModulePositions)

# Angular offsets of the modules relative to the chassis in radians
kFrontLeftChassisAngularOffset = 0
kFrontRightChassisAngularOffset = 0
kBackLeftChassisAngularOffset = 0
kBackRightChassisAngularOffset = 0

# SPARK MAX CAN IDs
kFrontLeftDrivingCanId = 5
kRearLeftDrivingCanId = 7
kFrontRightDrivingCanId = 1
kRearRightDrivingCanId = 3

kFrontLeftTurningCanId = 6
kRearLeftTurningCanId = 8
kFrontRightTurningCanId = 2
kRearRightTurningCanId = 4

kGyroReversed = False


class ModuleConstants:
# The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
# This changes the drive speed of the module (a pinion gear with more teeth will result in a
# robot that drives faster).
kDrivingMotorPinionTeeth = 17

# Invert the turning encoder, since the output shaft rotates in the opposite direction of
# the steering motor in the MAXSwerve Module.
kTurningEncoderInverted = True

# Calculations required for driving motor conversion factors and feed forward
kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60
kWheelDiameterMeters = 0.09525
kWheelCircumferenceMeters = kWheelDiameterMeters * math.pi
# 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
kDrivingMotorReduction = (60 * 34) / (kDrivingMotorPinionTeeth * 15)
kDriveWheelFreeSpeedRps = (
kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters
) / kDrivingMotorReduction

kDrivingEncoderPositionFactor = (
kWheelDiameterMeters * math.pi
) / kDrivingMotorReduction # meters
kDrivingEncoderVelocityFactor = (
(kWheelDiameterMeters * math.pi) / kDrivingMotorReduction
) / 60.0 # meters per second

kTurningEncoderPositionFactor = math.tau # radian
kTurningEncoderVelocityFactor = math.tau / 60.0 # radians per second

kTurningEncoderPositionPIDMinInput = 0 # radian
kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor # radian

kDrivingP = 0.04
kDrivingI = 0
kDrivingD = 0
kDrivingFF = 1 / kDriveWheelFreeSpeedRps
kDrivingMinOutput = -1
kDrivingMaxOutput = 1

kTurningP = 1
kTurningI = 0
kTurningD = 0.1
kTurningFF = 0
kTurningMinOutput = -1
kTurningMaxOutput = 1

kDrivingMotorIdleMode = CANSparkMax.IdleMode.kBrake
kTurningMotorIdleMode = CANSparkMax.IdleMode.kBrake

kDrivingMotorCurrentLimit = 50 # amp
kTurningMotorCurrentLimit = 20 # amp


class OIConstants:
kDriverControllerPort = 0
kDriveDeadband = 0.075


class AutoConstants:
kMaxSpeedMetersPerSecond = 3
kMaxAccelerationMetersPerSecondSquared = 3
kMaxAngularSpeedRadiansPerSecond = math.pi
kMaxAngularSpeedRadiansPerSecondSquared = math.pi

kPXController = 1
kPYController = 1
kPThetaController = 1

# Constraint for the motion profiled robot angle controller
kThetaControllerConstraints = TrapezoidProfileRadians.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared
)
Empty file removed rio/constants/__init__.py
Empty file.
44 changes: 0 additions & 44 deletions rio/constants/constants.py

This file was deleted.

34 changes: 0 additions & 34 deletions rio/constants/robot_controls.yaml

This file was deleted.

Loading

0 comments on commit 9b5326e

Please sign in to comment.