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

Feature/arm 2024 #7

Open
wants to merge 22 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 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
20 changes: 7 additions & 13 deletions src/main/java/frc/robot/subsystems/arm/ArmIOReal.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
package frc.robot.subsystems.arm;


import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.Slot1Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.*;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;
Expand Down Expand Up @@ -45,9 +42,7 @@ public class ArmIOReal implements ArmIO {
private ControlRequest motorControlRequest = null;




ArmIOReal() {
public ArmIOReal() {

this.shoulderEncoder = new DutyCycleEncoder(Ports.ArmPorts.SHOULDER_ENCODER);
this.elbowEncoder = new DutyCycleEncoder(Ports.ArmPorts.ELBOW_ENCODER);
Expand All @@ -61,7 +56,6 @@ public class ArmIOReal implements ArmIO {
this.elbowAuxMotor = new TalonFX(Ports.ArmPorts.ELBOW_AUX_MOTOR);



shoulderAuxMotor.setControl(new StrictFollower(shoulderMainMotor.getDeviceID()));
elbowAuxMotor.setControl(new StrictFollower(elbowMainMotor.getDeviceID()));

Expand Down Expand Up @@ -199,7 +193,7 @@ private void setElbowJointAngle(double angle, double ffMultiplier, int velocity)
public Translation2d getEndPosition() {
Rotation2d shoulderAngle = getShoulderJointAngle();
Rotation2d elbowAngle = getElbowJointAngle();
return kinematics.forwardKinematics(shoulderAngle.getRadians(),shoulderAngle.getRadians() + elbowAngle.getRadians() - Math.PI);
return kinematics.forwardKinematics(shoulderAngle.getRadians(), shoulderAngle.getRadians() + elbowAngle.getRadians() - Math.PI);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Kinematics should work with Rotation2d too.

}

/**
Expand Down Expand Up @@ -234,7 +228,7 @@ public double getShoulderMotorVelocity() {

public void setFinalSetpointAngles(Translation2d position, ArmInputs inputs) {
var solution = kinematics.inverseKinematics(position);
inputs.finalSetpointAngles = new Translation2d( Math.toDegrees(solution.shoulderAngle), Math.toDegrees(solution.elbowAngle));
inputs.finalSetpointAngles = new Translation2d(Math.toDegrees(solution.shoulderAngle), Math.toDegrees(solution.elbowAngle));
}

/**
Expand All @@ -255,10 +249,10 @@ public void resetArmEncoders() {

public Translation2d getElbowJointPosition() {
Rotation2d shoulderAngle = getShoulderJointAngle();
return new Translation2d(
SHOULDER_ARM_LENGTH,
shoulderAngle
);
return new Translation2d(
SHOULDER_ARM_LENGTH,
shoulderAngle
);
}

public boolean armIsOutOfFrame() {
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/arm/ArmInputs.java
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would say to put this class in the io interface, but this is enormous, so I get it.

Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import org.littletonrobotics.junction.AutoLog;
import org.littletonrobotics.junction.LogTable;
import org.littletonrobotics.junction.inputs.LoggableInputs;

Expand Down Expand Up @@ -44,7 +45,7 @@ public class ArmInputs implements LoggableInputs {
ArmIO.ControlMode elbowControlMode;


@Override

public void toLog(LogTable table) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In your case you can remove toLog and fromLog and just use @AutoLog.

table.put("shoulderAngle", shoulderAngle);
table.put("elbowAngle", elbowAngle);
Expand Down