Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updating libraries and more #1

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
51 changes: 51 additions & 0 deletions .github/workflows/Build_and_Simulate.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# This is a basic workflow to build robot code.

name: Build_and_Simulate

# Controls when the action will run. Triggers the workflow on push or pull request
# events but only for the main branch.
on:
push:
branches: [ main ]
pull_request:
branches: [ main ]

# A workflow run is made up of one or more jobs that can run sequentially or in parallel
jobs:
# This workflow contains a single job called "build"
BuildSim:
# The type of runner that the job will run on
runs-on: ubuntu-latest

# This grabs the WPILib docker container
container: wpilib/roborio-cross-ubuntu:2024-22.04

# Steps represent a sequence of tasks that will be executed as part of the job
steps:
# Checks-out your repository under $GITHUB_WORKSPACE, so your job can access it
- uses: actions/checkout@v4

# Declares the repository safe and not under dubious ownership.
- name: Add repository to git safe directories
run: git config --global --add safe.directory $GITHUB_WORKSPACE

# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
run: chmod +x gradlew


# Runs a single command using the runners shell
- name: Build robot code
run: ./gradlew build

- name: Simulate Robot Code
id: Simulation
continue-on-error: true
run: |
timeout 15s ./gradlew simulateJava

- name: Check if simulation was able to run for full time or if it exited early
run: |
exit $Code
env:
Code: ${{steps.simulation.outcome == 'failure' && '0' || '1'}}
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -56,5 +56,6 @@
"edu.wpi.first.math.proto.*",
"edu.wpi.first.math.**.proto.*",
"edu.wpi.first.math.**.struct.*",
]
],
"java.format.settings.url": "eclipse-formatter.xml"
}
Empty file modified gradlew
100644 → 100755
Empty file.
23 changes: 18 additions & 5 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,13 @@
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
},
{
"decKey": 75,
"incKey": 76
}
],
"axisCount": 3,
"axisCount": 5,
"buttonCount": 4,
"buttonKeys": [
90,
Expand All @@ -42,12 +46,10 @@
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
"decKey": 74
},
{
"decKey": 73,
"incKey": 75
"decKey": 73
}
],
"axisCount": 2,
Expand Down Expand Up @@ -88,5 +90,16 @@
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"guid": "030000005e0400008e02000014010000"
},
{
"guid": "030000004c050000c405000000000000"
},
{
"useGamepad": true
}
]
}
8 changes: 8 additions & 0 deletions src/main/deploy/swerve/neo/controllerproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
{
"angleJoystickRadiusDeadband": 0.5,
"heading": {
"p": 0.4,
"i": 0,
"d": 0.01
}
}
26 changes: 26 additions & 0 deletions src/main/deploy/swerve/neo/modules/backleft.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
{
"drive": {
"type": "sparkmax_neo",
"id": 7,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 8,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 12,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": 6.504,
"location": {
"front": -12,
"left": 12
}
}
26 changes: 26 additions & 0 deletions src/main/deploy/swerve/neo/modules/backright.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
{
"drive": {
"type": "sparkmax_neo",
"id": 5,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 6,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 11,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -18.281,
"location": {
"front": -12,
"left": -12
}
}
26 changes: 26 additions & 0 deletions src/main/deploy/swerve/neo/modules/frontleft.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
{
"drive": {
"type": "sparkmax_neo",
"id": 4,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 3,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 9,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -114.609,
"location": {
"front": 12,
"left": 12
}
}
26 changes: 26 additions & 0 deletions src/main/deploy/swerve/neo/modules/frontright.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
{
"drive": {
"type": "sparkmax_neo",
"id": 2,
"canbus": null
},
"angle": {
"type": "sparkmax_neo",
"id": 1,
"canbus": null
},
"encoder": {
"type": "cancoder",
"id": 10,
"canbus": null
},
"inverted": {
"drive": false,
"angle": false
},
"absoluteEncoderOffset": -50.977,
"location": {
"front": 12,
"left": -12
}
}
23 changes: 23 additions & 0 deletions src/main/deploy/swerve/neo/modules/physicalproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
{
"conversionFactors": {
"angle": {
"gearRatio": 12.8,
"factor": 0
},
"drive": {
"gearRatio": 8.14,
"diameter": 4,
"factor": 0
}
},
"currentLimit": {
"drive": 40,
"angle": 20
},
"rampRate": {
"drive": 0.25,
"angle": 0.25
},
"wheelGripCoefficientOfFriction": 1.19,
"optimalVoltage": 12
}
16 changes: 16 additions & 0 deletions src/main/deploy/swerve/neo/modules/pidfproperties.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
{
"drive": {
"p": 0.00023,
"i": 0.0000002,
"d": 1,
"f": 0,
"iz": 0
},
"angle": {
"p": 0.0020645,
"i": 0,
"d": 0,
"f": 0.001,
"iz": 0
}
}
14 changes: 14 additions & 0 deletions src/main/deploy/swerve/neo/swervedrive.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
{
"imu": {
"type": "pigeon2",
"id": 13,
"canbus": "canivore"
},
"invertedIMU": true,
"modules": [
"frontleft.json",
"frontright.json",
"backleft.json",
"backright.json"
]
}
43 changes: 42 additions & 1 deletion src/main/java/com/spartronics4915/frc2025/Constants.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,46 @@
// 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 com.spartronics4915.frc2025;

public class Constants {
import edu.wpi.first.math.util.Units;

/**
* The Constants class provides a convenient place for teams to hold robot-wide
* numerical or boolean
* constants. This class should not be used for any other purpose. All constants
* should be declared
* globally (i.e. public static). Do not put anything functional in this class.
*
* <p>
* It is advised to statically import this class (or one of its inner classes)
* wherever the
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final class OI {
public static final int kDriverControllerPort = 0;
public static final int kOperatorControllerPort = 1;

public static final double kStickDeadband = 0.05;

public static final double kDriverTriggerDeadband = 0.3;
public static final double kOperatorTriggerDeadband = 0.3;
}

public static final class Drive {
public static final double kTrackWidth = Units.inchesToMeters(22.475);
public static final double kWheelbase = Units.inchesToMeters(22.475);
public static final double kChassisRadius = Math.hypot(
kTrackWidth / 2, kWheelbase / 2);

public static final double kMaxSpeed = Units.feetToMeters(15.1);
public static final double kMaxAngularSpeed = kMaxSpeed * Math.PI / kChassisRadius;

}

public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
}
}
10 changes: 10 additions & 0 deletions src/main/java/com/spartronics4915/frc2025/Main.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,19 @@

import edu.wpi.first.wpilibj.RobotBase;

/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
* you are doing, do not modify this file except to change the parameter class to the startRobot
* call.
*/
public final class Main {
private Main() {}

/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
Expand Down
Loading
Loading