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

Ofir #8

Open
wants to merge 49 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
49 commits
Select commit Hold shift + click to select a range
5ad3e66
Constants
ofirKAMInetsky Nov 9, 2023
8e2b938
Update ArmConstants.java
ofirKAMInetsky Nov 9, 2023
99e624e
Update ArmConstants.java
ofirKAMInetsky Nov 9, 2023
8769ff4
updated ArmConstants
ofirKAMInetsky Nov 13, 2023
7a39af8
updated ArmConstants
ofirKAMInetsky Nov 13, 2023
8128bdf
updated ArmConstants.java
ofirKAMInetsky Nov 13, 2023
2328764
Update ArmConstants.java
ofirKAMInetsky Nov 13, 2023
28a7ab0
FIX
ofirKAMInetsky Nov 13, 2023
82882a0
FIX
ofirKAMInetsky Nov 13, 2023
99805bb
changed the names
ofirKAMInetsky Nov 14, 2023
773f4f3
___FIXED___
ofirKAMInetsky Nov 14, 2023
113172a
Update ArmConstants.java
ofirKAMInetsky Nov 14, 2023
cb29753
Update ArmConstants.java
ofirKAMInetsky Nov 15, 2023
b5f06cb
Update ArmConstants.java
ofirKAMInetsky Nov 15, 2023
b10639e
Create ArmSubsystem.java
ofirKAMInetsky Nov 16, 2023
75998fa
Update ArmConstants.java
ofirKAMInetsky Nov 16, 2023
50fbce0
____added___motors___
ofirKAMInetsky Nov 16, 2023
b75612e
made it static
ofirKAMInetsky Nov 16, 2023
32bb477
Update ArmSubsystem.java
ofirKAMInetsky Nov 16, 2023
ca981c8
==!!!___updated___!!!==
ofirKAMInetsky Nov 16, 2023
2385256
i dont know what it is
ofirKAMInetsky Nov 16, 2023
1dcd1e4
added angle methods
ofirKAMInetsky Nov 16, 2023
1372f92
I added the profile of the elevator
ofirKAMInetsky Nov 17, 2023
656b3d8
corrected the last profile generate
ofirKAMInetsky Nov 17, 2023
2227ae3
added and fixed things
ofirKAMInetsky Nov 19, 2023
f8d3f49
Update Arm.java
ofirKAMInetsky Nov 19, 2023
aa18345
Fixed .run folder
ofirKAMInetsky Nov 19, 2023
41faad4
Fixed the .gitignore file
ofirKAMInetsky Nov 19, 2023
097d24d
Revert "Fixed .run folder"
ofirKAMInetsky Nov 19, 2023
fc7840a
Fixed the .run folder
ofirKAMInetsky Nov 19, 2023
bb4e12b
Update Arm.java
ofirKAMInetsky Nov 19, 2023
6586e6d
Update ArmConstants.java
ofirKAMInetsky Nov 19, 2023
847ed6d
fixed something
ofirKAMInetsky Nov 19, 2023
b19c37d
fix
ofirKAMInetsky Nov 19, 2023
14a9e97
!@#$%^&*()_FIX_)(*&^%$#@!
ofirKAMInetsky Nov 19, 2023
2aa4458
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!--FIX--!!!!!!!!!!!!!!!!!!…
ofirKAMInetsky Nov 19, 2023
a35019b
FFFFFFFFFFFFFIXXXXXXXXXXXXXXX
ofirKAMInetsky Nov 19, 2023
2f10641
Update Arm.java
ofirKAMInetsky Nov 19, 2023
ddae22a
Update Arm.java
ofirKAMInetsky Nov 20, 2023
a8023f9
Merge branch 'main' into arm
ofirKAMInetsky Nov 23, 2023
77bd329
-=+=-__FIX__added the Deferred Command__FIX__-=+=-
ofirKAMInetsky Nov 23, 2023
6e55d4c
updated and fixed
ofirKAMInetsky Nov 23, 2023
7a8efe6
Update Arm.java
ofirKAMInetsky Nov 23, 2023
fc4b2b5
Update Arm.java
ofirKAMInetsky Nov 26, 2023
71b1adb
Update Arm.java
ofirKAMInetsky Nov 26, 2023
a5dc6d7
Update Arm.java
ofirKAMInetsky Dec 4, 2023
aecf2a1
Update Arm.java
ofirKAMInetsky Dec 17, 2023
af693b1
Update Arm.java
ofirKAMInetsky Dec 20, 2023
6f5dbc0
Moved all the commands ArmCommands class.
ofirKAMInetsky Dec 29, 2023
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
12 changes: 9 additions & 3 deletions .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,24 @@
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
"version": "0.2.0",
"configurations": [

{
"type": "java",
"name": "Launch Main",
"request": "launch",
"mainClass": "frc.trigon.robot.Main",
"projectName": ""
},
{
"type": "wpilib",
"name": "WPILib Desktop Debug",
"request": "launch",
"desktop": true,
"desktop": true
},
{
"type": "wpilib",
"name": "WPILib roboRIO Debug",
"request": "launch",
"desktop": false,
"desktop": false
}
]
}
180 changes: 180 additions & 0 deletions src/main/java/frc/trigon/robot/subsystems/arm/Arm.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,180 @@
package frc.trigon.robot.subsystems.arm;

import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.*;
import frc.trigon.robot.utilities.Conversions;

import java.util.Set;

public class Arm extends SubsystemBase {
private final static Arm INSTANCE = new Arm();

private final CANSparkMax
masterAngleMotor = ArmConstants.MASTER_ANGLE_MOTOR,
followerAngleMotor = ArmConstants.FOLLOWER_ANGLE_MOTOR,
masterElevatorMotor = ArmConstants.MASTER_ELEVATOR_MOTOR,
followerElevatorMotor = ArmConstants.FOLLOWER_ELEVATOR_MOTOR;
private final TalonSRX elevatorEncoder = ArmConstants.ELEVATOR_ENCODER;

private TrapezoidProfile
angleMotorProfile = null,
elevatorMotorProfile = null;
private double
lastAngleProfileGenerationTime,
lastElevatorProfileGenerationTime;

public static Arm getInstance() {
return INSTANCE;
}

private Arm() {
}

Command getCurrentSetTargetStateCommand(double elevatorPosition, Rotation2d angle, double angleSpeedPercentage, double elevatorSpeedPercentage) {
if (isElevatorOpening(elevatorPosition)) {
return new SequentialCommandGroup(
getSetTargetAngleCommand(angle, angleSpeedPercentage),
getSetTargetElevatorPositionCommand(elevatorPosition, elevatorSpeedPercentage)
);
}
return new SequentialCommandGroup(
getSetTargetElevatorPositionCommand(elevatorPosition, elevatorSpeedPercentage),
getSetTargetAngleCommand(angle, angleSpeedPercentage)
);
}

private Command getSetTargetElevatorPositionCommand(double targetElevatorPosition, double speedPercentage) {
return new FunctionalCommand(
() -> generateElevatorMotorProfile(targetElevatorPosition, speedPercentage),
this::setTargetElevatorFromProfile,
(interrupted) -> {
},
() -> false,
this
);
}

private Command getSetTargetAngleCommand(Rotation2d angle, double angleSpeedPercentage) {
return new FunctionalCommand(
() -> generateAngleMotorProfile(angle, angleSpeedPercentage),
this::setTargetAngleFromProfile,
(interrupted) -> {
},
() -> false,
this
);
}

private boolean isElevatorOpening(double targetElevatorPosition) {
return targetElevatorPosition > getElevatorPositionRevolutions();
}

private void generateAngleMotorProfile(Rotation2d targetAngle, double speedPercentage) {
angleMotorProfile = new TrapezoidProfile(
Conversions.scaleConstraints(ArmConstants.ANGLE_CONSTRAINS, speedPercentage),
new TrapezoidProfile.State(targetAngle.getDegrees(), 0),
new TrapezoidProfile.State(getAnglePosition().getDegrees(), getAngleVelocityDegreesPerSecond())
);
lastAngleProfileGenerationTime = Timer.getFPGATimestamp();
}

private void generateElevatorMotorProfile(double targetElevator, double speedPercentage) {
elevatorMotorProfile = new TrapezoidProfile(
Conversions.scaleConstraints(ArmConstants.ELEVATOR_CONSTRAINS, speedPercentage),
new TrapezoidProfile.State(targetElevator, 0),
new TrapezoidProfile.State(getElevatorPositionRevolutions(), getElevatorVelocityRevolutionsPerSecond())
);
lastElevatorProfileGenerationTime = Timer.getFPGATimestamp();
}

private void setTargetAngleFromProfile() {
if (angleMotorProfile == null) {
stopAngleMotors();
return;
}
TrapezoidProfile.State targetState = angleMotorProfile.calculate(getAngleMotorProfileTime());
setAngleMotorsVoltage(calculateAngleMotorOutput(targetState));
}

private void setTargetElevatorFromProfile() {
if (elevatorMotorProfile == null) {
stopElevatorMotors();
return;
}
TrapezoidProfile.State targetState = elevatorMotorProfile.calculate(getElevatorMotorProfileTime());
setElevatorMotorsVoltage(calculateElevatorMotorOutput(targetState));
}

private double getAngleMotorProfileTime() {
return Timer.getFPGATimestamp() - lastAngleProfileGenerationTime;
}

private double getElevatorMotorProfileTime() {
return Timer.getFPGATimestamp() - lastElevatorProfileGenerationTime;
}

private double calculateAngleMotorOutput(TrapezoidProfile.State targetState) {
double pidOutput = ArmConstants.ANGLE_PID_CONTROLLER.calculate(
getAnglePosition().getDegrees(),
targetState.position
);
double feedforward = ArmConstants.ANGLE_MOTOR_FEEDFORWARD.calculate(
Units.degreesToRadians(targetState.position),
Units.degreesToRadians(targetState.velocity)
);
return feedforward + pidOutput;
}

private double calculateElevatorMotorOutput(TrapezoidProfile.State targetState) {
double pidOutput = ArmConstants.ELEVATOR_PID_CONTROLLER.calculate(
getElevatorPositionRevolutions(),
targetState.position
);
double feedforward = ArmConstants.ELEVATOR_MOTOR_FEEDFORWARD.calculate(targetState.velocity);
return feedforward + pidOutput;
}

private double getAngleVelocityDegreesPerSecond() {
double positionRevolutions = ArmConstants.ANGLE_VELOCITY_SIGNAL.refresh().getValue();
return Conversions.revolutionsToDegrees(positionRevolutions);
}

private double getElevatorVelocityRevolutionsPerSecond() {
double magTicksPerSecond = Conversions.perHundredMsToPerSecond(elevatorEncoder.getSelectedSensorVelocity());
return Conversions.magTicksToRevolutions(magTicksPerSecond);
}

private Rotation2d getAnglePosition() {
double positionRevolutions = ArmConstants.ANGLE_POSITION_SIGNAL.refresh().getValue();
return Rotation2d.fromRotations(positionRevolutions);
}

private double getElevatorPositionRevolutions() {
return Conversions.magTicksToRevolutions(elevatorEncoder.getSelectedSensorPosition());
}

private void stopAngleMotors() {
masterAngleMotor.stopMotor();
followerAngleMotor.stopMotor();
}

private void stopElevatorMotors() {
masterElevatorMotor.stopMotor();
followerElevatorMotor.stopMotor();
}

private void setAngleMotorsVoltage(double voltage) {
masterAngleMotor.setVoltage(voltage);
followerAngleMotor.setVoltage(voltage);
}

private void setElevatorMotorsVoltage(double voltage) {
masterElevatorMotor.setVoltage(voltage);
followerElevatorMotor.setVoltage(voltage);
}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/trigon/robot/subsystems/arm/ArmCommands.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package frc.trigon.robot.subsystems.arm;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.DeferredCommand;

import java.util.Set;

public class ArmCommands {
private static final Arm ARM = Arm.getInstance();

public Command getSetTargetArmStateCommand(ArmConstants.ArmState targetState) {
return getSetTargetArmStateCommand(targetState.elevatorPositionMeters, targetState.angle, 100, 100);
}

public Command getSetTargetArmStateCommand(ArmConstants.ArmState targetState, double angleSpeedPercentage, double elevatorSpeedPercentage) {
return getSetTargetArmStateCommand(targetState.elevatorPositionMeters, targetState.angle, angleSpeedPercentage, elevatorSpeedPercentage);
}

public Command getSetTargetArmStateCommand(double elevatorPosition, Rotation2d angle, double angleSpeedPercentage, double elevatorSpeedPercentage) {
return new DeferredCommand(
() -> ARM.getCurrentSetTargetStateCommand(elevatorPosition, angle, angleSpeedPercentage, elevatorSpeedPercentage),
Set.of(ARM)
);
}

public Command getSetTargetArmPositionCommand(double elevatorPosition, Rotation2d angle) {
return new DeferredCommand(
() -> ARM.getCurrentSetTargetStateCommand(elevatorPosition, angle, 100, 100),
Set.of(ARM)
);
}
}
Loading