Skip to content
This repository has been archived by the owner on Aug 23, 2024. It is now read-only.

Commit

Permalink
Fixed bugs and bumped last stuff to 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
Daniel1464 committed Jan 11, 2024
1 parent 8e4c95b commit ee7f4b7
Show file tree
Hide file tree
Showing 7 changed files with 47 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ public final class ChargerLibBuildConstants {
public static final String MAVEN_GROUP = "frc.chargers";
public static final String MAVEN_NAME = "ChargerLib";
public static final String VERSION = "1.0.0";
public static final int GIT_REVISION = 263;
public static final String GIT_SHA = "6bb441ebd5b1c371fa0748f56df6dccb49fd3469";
public static final String GIT_DATE = "2024-01-09T16:23:13Z";
public static final int GIT_REVISION = 264;
public static final String GIT_SHA = "8e4c95b743ed5868a6845f080b865f9124e386e9";
public static final String GIT_DATE = "2024-01-10T21:55:23Z";
public static final String GIT_BRANCH = "master";
public static final String BUILD_DATE = "2024-01-09T22:00:16Z";
public static final long BUILD_UNIX_TIME = 1704855616439L;
public static final String BUILD_DATE = "2024-01-10T22:08:12Z";
public static final long BUILD_UNIX_TIME = 1704942492477L;
public static final int DIRTY = 1;

private ChargerLibBuildConstants(){}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@ import com.batterystaple.kmeasure.units.grams
import com.batterystaple.kmeasure.units.kilo
import com.batterystaple.kmeasure.units.meters
import com.batterystaple.kmeasure.units.seconds
import frc.chargers.utils.math.units.Inertia
import frc.chargers.utils.math.units.times

/*
Note: @PublishedApi makes internal values accessible to inline functions.
Expand All @@ -21,13 +19,7 @@ internal val DEFAULT_MAX_MODULE_SPEED: Velocity = 4.5.ofUnit(meters / seconds)
internal const val DEFAULT_GEAR_RATIO: Double = 1.0

@PublishedApi
internal val DEFAULT_SWERVE_TURN_INERTIA: Inertia = 0.025.ofUnit(kilo.grams * meters * meters)
internal val DEFAULT_SWERVE_TURN_INERTIA: MomentOfInertia = 0.025.ofUnit(kilo.grams * (meters * meters) )

@PublishedApi
internal val DEFAULT_SWERVE_DRIVE_INERTIA: Inertia = 0.004096955.ofUnit(kilo.grams * meters * meters)


internal const val DEFAULT_MAX_STEERING_POWER: Double = 0.3


internal val DEFAULT_MAX_STEERING_VELOCITY: AngularVelocity = AngularVelocity(0.3)
internal val DEFAULT_SWERVE_DRIVE_INERTIA: MomentOfInertia = 0.004096955.ofUnit(kilo.grams * (meters * meters) )
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package frc.chargers.hardware.subsystems.differentialdrive

import edu.wpi.first.wpilibj.drive.DifferentialDrive
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup
import edu.wpi.first.wpilibj.motorcontrol.MotorController
import edu.wpi.first.wpilibj2.command.SubsystemBase


Expand All @@ -11,8 +11,8 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase
* @see DifferentialDrivetrain
*/
public open class BasicDifferentialDrivetrain(
leftMotors: MotorControllerGroup,
rightMotors: MotorControllerGroup,
leftMotors: MotorController,
rightMotors: MotorController,
invertMotors: Boolean = false,
protected val powerScale: Double = 1.0,
protected val rotationScale: Double = 1.0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,35 +10,37 @@ import com.pathplanner.lib.auto.AutoBuilder
import edu.wpi.first.math.kinematics.ChassisSpeeds
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds
import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim
import edu.wpi.first.wpilibj2.command.SubsystemBase
import frc.chargers.advantagekitextensions.LoggableInputsProvider
import frc.chargers.constants.drivetrain.DiffDriveControlData
import frc.chargers.constants.drivetrain.DiffDriveHardwareData
import frc.chargers.controls.SetpointSupplier
import frc.chargers.controls.pid.SuperPIDController
import frc.chargers.hardware.configuration.HardwareConfiguration
import frc.chargers.hardware.motorcontrol.ctre.ChargerTalonFXConfiguration
import frc.chargers.hardware.sensors.imu.gyroscopes.HeadingProvider
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIO
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIOReal
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIOSim
import frc.chargers.constants.drivetrain.DiffDriveControlData
import frc.chargers.controls.feedforward.Feedforward
import frc.chargers.controls.pid.SuperPIDController
import frc.chargers.framework.ChargerRobot
import frc.chargers.hardware.configuration.HardwareConfigurable
import frc.chargers.hardware.configuration.HardwareConfiguration
import frc.chargers.hardware.motorcontrol.EncoderMotorController
import frc.chargers.hardware.motorcontrol.ctre.ChargerTalonFX
import frc.chargers.hardware.motorcontrol.ctre.ChargerTalonFXConfiguration
import frc.chargers.hardware.motorcontrol.rev.ChargerSparkMax
import frc.chargers.hardware.motorcontrol.rev.ChargerSparkMaxConfiguration
import frc.chargers.hardware.sensors.RobotPoseMonitor
import frc.chargers.hardware.sensors.VisionPoseSupplier
import frc.chargers.hardware.sensors.imu.gyroscopes.HeadingProvider
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIO
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIOReal
import frc.chargers.hardware.subsystems.differentialdrive.lowlevel.DiffDriveIOSim
import frc.chargers.utils.a
import frc.chargers.wpilibextensions.geometry.ofUnit
import frc.chargers.wpilibextensions.geometry.twodimensional.UnitPose2d
import frc.chargers.wpilibextensions.kinematics.ChassisSpeeds
import org.littletonrobotics.junction.Logger.recordOutput


private val standardLogInputs = LoggableInputsProvider(namespace = "Drivetrain(Differential)")


Expand Down Expand Up @@ -163,6 +165,16 @@ public class EncoderDifferentialDrivetrain(
selfSustain = true,
)

private fun shouldFlipAlliance(): Boolean{
// Boolean supplier that controls when the path will be mirrored for the red alliance
// This will flip the path being followed to the red side of the field.
// THE ORIGIN WILL REMAIN ON THE BLUE SIDE
val alliance = DriverStation.getAlliance()
return if (alliance.isPresent) {
alliance.get() == DriverStation.Alliance.Red
} else false
}


/* Public API */

Expand All @@ -177,6 +189,7 @@ public class EncoderDifferentialDrivetrain(
{ speeds: ChassisSpeeds -> velocityDrive(speeds) },
ChargerRobot.LOOP_PERIOD.inUnit(seconds),
controlData.pathReplanConfig,
::shouldFlipAlliance,
this
)
}
Expand All @@ -188,6 +201,7 @@ public class EncoderDifferentialDrivetrain(
{ currentSpeeds },
{ speeds: ChassisSpeeds -> velocityDrive(speeds) },
controlData.pathReplanConfig,
::shouldFlipAlliance,
this
)
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ import frc.chargers.wpilibextensions.geometry.twodimensional.UnitTranslation2d
import frc.chargers.wpilibextensions.geometry.twodimensional.asRotation2d
import frc.chargers.wpilibextensions.kinematics.*
import org.littletonrobotics.junction.Logger.*
import java.util.Optional
import kotlin.math.pow


Expand Down Expand Up @@ -274,6 +275,13 @@ public class EncoderHolonomicDrivetrain(
kotlin.math.sqrt(hardwareData.trackWidth.inUnit(meters).pow(2) + hardwareData.wheelBase.inUnit(meters).pow(2)),
controlData.pathReplanConfig
),
{
when (val alliance = DriverStation.getAlliance()){
Optional.empty<DriverStation.Alliance>() -> false

else -> alliance.get() == DriverStation.Alliance.Red
}
},
this
)
}
Expand All @@ -285,7 +293,7 @@ public class EncoderHolonomicDrivetrain(
/**
* The pose estimator of the [EncoderHolonomicDrivetrain].
*
* This can be changed to a different pose monitor if nessecary.
* This can be changed to a different pose monitor if necessary.
*/
public var poseEstimator: RobotPoseMonitor = SwervePoseMonitor(
drivetrain = this,
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/NavX.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "NavX.json",
"name": "NavX",
"version": "2024.0.1-beta-4",
"version": "2024.1.0",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-java",
"version": "2024.0.1-beta-4"
"version": "2024.1.0"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-cpp",
"version": "2024.0.1-beta-4",
"version": "2024.1.0",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": false,
Expand Down
6 changes: 3 additions & 3 deletions vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "PathplannerLib.json",
"name": "PathplannerLib",
"version": "2024.0.0-beta-4",
"version": "2024.1.2",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,15 +12,15 @@
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-java",
"version": "2024.0.0-beta-4"
"version": "2024.1.2"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.pathplanner.lib",
"artifactId": "PathplannerLib-cpp",
"version": "2024.0.0-beta-4",
"version": "2024.1.2",
"libName": "PathplannerLib",
"headerClassifier": "headers",
"sharedLibrary": false,
Expand Down

0 comments on commit ee7f4b7

Please sign in to comment.