This repository has been archived by the owner on Dec 11, 2024. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 0
Storm surge #91
Merged
Merged
Storm surge #91
Changes from all commits
Commits
Show all changes
6 commits
Select commit
Hold shift + click to select a range
File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -38,7 +38,6 @@ import org.littletonrobotics.junction.LogTable | |
import org.littletonrobotics.junction.Logger | ||
import org.littletonrobotics.junction.inputs.LoggableInputs | ||
import java.util.* | ||
import kotlin.math.PI | ||
import kotlin.math.abs | ||
|
||
// A singleton object representing the drivetrain. | ||
|
@@ -47,7 +46,7 @@ object Drivetrain : Subsystem, TalonFXStatusProvider { | |
/** Unit: Percent of max robot speed */ | ||
private const val TRANSLATION_SENSITIVITY = 1.0 | ||
/** Unit: Rotations per second */ | ||
private const val ROTATION_SENSITIVITY = 0.9 | ||
private const val ROTATION_SENSITIVITY = 1.25 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. 1.25 comes from getting joystick control that felt good to Calvin. Note this. |
||
|
||
private val io = when (Robot.model) { | ||
Robot.Model.SIMULATION -> DrivetrainIOSim() | ||
|
@@ -246,7 +245,7 @@ object Drivetrain : Subsystem, TalonFXStatusProvider { | |
|| abs(rotationJoystick.x) > JOYSTICK_DEADBAND | ||
) { | ||
val translationInput = | ||
Translation2d(-translationJoystick.y, -translationJoystick.x).rotateBy(DRIVER_ROTATION) | ||
Translation2d(-translationJoystick.y, -translationJoystick.x) | ||
|
||
chassisSpeeds = | ||
ChassisSpeeds.fromFieldRelativeSpeeds( | ||
|
@@ -281,28 +280,31 @@ object Drivetrain : Subsystem, TalonFXStatusProvider { | |
enableContinuousInput(0.0, TAU) | ||
} | ||
return run { | ||
val translationInput = if (abs(translationJoystick.x) > JOYSTICK_DEADBAND | ||
|| abs(translationJoystick.y) > JOYSTICK_DEADBAND | ||
) { | ||
Translation2d(-translationJoystick.y, -translationJoystick.x) | ||
} else { | ||
Translation2d() | ||
} | ||
val magnitude = rotationPIDController.calculate( | ||
target.minus(estimatedPose.translation).angle.radians - (TAU/2), | ||
estimatedPose.rotation.radians | ||
) | ||
|
||
chassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds( | ||
translationJoystick.y * FREE_SPEED.baseUnitMagnitude(), | ||
translationJoystick.x * FREE_SPEED.baseUnitMagnitude(), | ||
magnitude, | ||
gyroRotation.toRotation2d(), | ||
translationInput.x * FREE_SPEED.baseUnitMagnitude() * TRANSLATION_SENSITIVITY, | ||
translationInput.y * FREE_SPEED.baseUnitMagnitude() * TRANSLATION_SENSITIVITY, | ||
-magnitude, | ||
gyroRotation.toRotation2d() | ||
) | ||
} | ||
} | ||
|
||
fun zeroGyro() { | ||
// When zeroing the gyro happens, the robot is facing the speaker-side. | ||
// This is a different direction on the red vs. blue sides. | ||
gyroRotation = if (DriverStation.getAlliance() == Optional.of(DriverStation.Alliance.Red)) { | ||
Rotation3d(0.0, 0.0, PI) | ||
} else { | ||
Rotation3d() | ||
} | ||
gyroRotation = Rotation3d() | ||
} | ||
|
||
@Suppress("unused") | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -3,7 +3,6 @@ package com.frcteam3636.frc2024.subsystems.shooter | |
import com.ctre.phoenix6.StatusSignal | ||
import com.ctre.phoenix6.configs.TalonFXConfiguration | ||
import com.ctre.phoenix6.controls.MotionMagicTorqueCurrentFOC | ||
import com.ctre.phoenix6.controls.PositionTorqueCurrentFOC | ||
import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC | ||
import com.ctre.phoenix6.controls.VoltageOut | ||
import com.ctre.phoenix6.signals.GravityTypeValue | ||
|
@@ -200,7 +199,7 @@ class PivotIOKraken : PivotIO { | |
override fun pivotToAndMove(position: Rotation2d, velocity: Rotation2d) { | ||
Logger.recordOutput("Shooter/Pivot/Position Setpoint", position) | ||
|
||
val leftControl = PositionTorqueCurrentFOC(0.0).apply { | ||
val leftControl = MotionMagicTorqueCurrentFOC(0.0).apply { | ||
Slot = 0 | ||
Position = position.rotations | ||
} | ||
|
@@ -264,7 +263,7 @@ class PivotIOKraken : PivotIO { | |
const val PROFILE_JERK = 80.0 | ||
|
||
val HARDSTOP_OFFSET: Rotation2d = Rotation2d.fromDegrees(-27.0) | ||
val ABSOLUTE_ENCODER_OFFSET: Rotation2d = Rotation2d.fromDegrees(229.5) + HARDSTOP_OFFSET | ||
val ABSOLUTE_ENCODER_OFFSET: Rotation2d = Rotation2d.fromDegrees(343.3) + HARDSTOP_OFFSET | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. where the hell did 343.3 come from? Explain in comment. |
||
} | ||
|
||
override val talonCANStatuses = listOf(leftMotor.version, rightMotor.version) | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -188,6 +188,8 @@ object Shooter { | |
|
||
var target: Target = Target.AIM | ||
|
||
var numTicks: Int = 0 | ||
|
||
|
||
private val processedAbsoluteEncoderPosition | ||
get() = | ||
|
@@ -196,7 +198,9 @@ object Shooter { | |
val encoderConnected get() = inputs.absoluteEncoderConnected | ||
|
||
override fun periodic() { | ||
val currentZero = zeroPos.getDouble(PivotIOKraken.ABSOLUTE_ENCODER_OFFSET.radians) | ||
numTicks++ | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. assert(numTicks <= 20 && numTicks >=0) |
||
// println(numTicks) | ||
// val currentZero = zeroPos.getDouble(PivotIOKraken.ABSOLUTE_ENCODER_OFFSET.radians) | ||
// io.offset = Rotation2d(currentZero) | ||
|
||
Logger.recordOutput("Shooter/Pivot/Offset Constant", PivotIOKraken.ABSOLUTE_ENCODER_OFFSET) | ||
|
@@ -205,7 +209,10 @@ object Shooter { | |
Logger.processInputs("Shooter/Pivot", inputs) | ||
|
||
val encoderPos = processedAbsoluteEncoderPosition | ||
io.setPivotPosition(encoderPos) | ||
if (numTicks == 20) { | ||
io.setPivotPosition(encoderPos) | ||
numTicks = 0 | ||
} | ||
Logger.recordOutput("Shooter/Pivot/Processed Encoder Position", encoderPos) | ||
Logger.recordOutput("Shooter/Pivot/Required Offset", -inputs.uncorrectedEncoderPosition) | ||
|
||
|
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We can delete this, right?