-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #2 from FRC-4509-MechBulls/✨arm✨
Arm tuned
- Loading branch information
Showing
8 changed files
with
484 additions
and
5 deletions.
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,83 @@ | ||
// 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 frc.robot.subsystems.arm; | ||
|
||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.RunCommand; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
import static frc.robot.Constants.ArmConstants.*; | ||
import frc.robot.Constants; | ||
|
||
import java.awt.geom.Point2D; | ||
|
||
public class Arm extends SubsystemBase { | ||
/** Creates a new Arm. */ | ||
// StageOneSub stageOneSub = new StageOneSub(); | ||
|
||
StageOneSub stageOneSub = new StageOneSub(); | ||
StageTwoSub stageTwoSub = new StageTwoSub(); | ||
|
||
|
||
public Arm() { | ||
|
||
// SmartDashboard.putNumber("stageOneRef",90); | ||
// SmartDashboard.putNumber("stageTwoRef",15); | ||
} | ||
|
||
|
||
|
||
public static double[] calculateEFPosition(double ang1, double ang2) { | ||
double stageOneEndX = stageOneLength * Math.cos(ang1); | ||
double stageOneEndY = stageOneLength * Math.sin(ang1); | ||
|
||
double stageTwoEndX = stageOneEndX + stageTwoLength * -Math.cos(ang1 + ang2); | ||
double stageTwoEndY = stageOneEndY + stageTwoLength * -Math.sin(ang1 + ang2); | ||
|
||
return new double[]{stageTwoEndX, stageTwoEndY}; | ||
} | ||
|
||
|
||
public static Rotation2d[] calculateArmAngles(double x, double y){ | ||
double hypot = Math.hypot(x,y); | ||
double stageTwoAngle = Math.acos((Math.pow(stageTwoLength,2) + Math.pow(stageOneLength,2) - Math.pow(hypot,2)) / (2*stageOneLength * stageTwoLength) ); | ||
double stageOneAngle = Math.acos((Math.pow(stageOneLength,2) + Math.pow(hypot,2) - Math.pow(stageTwoLength,2)) / (2*stageOneLength * hypot)); | ||
|
||
stageOneAngle+=Math.atan2(y,x); | ||
|
||
return new Rotation2d[] {Rotation2d.fromRadians(stageOneAngle),Rotation2d.fromRadians(stageTwoAngle)}; | ||
} | ||
|
||
@Override | ||
public void periodic() { | ||
// This method will be called once per scheduler run | ||
|
||
double[] efPosition = calculateEFPosition(stageOneSub.getAngle().getRadians(), stageTwoSub.getAngle().getRadians()); | ||
|
||
SmartDashboard.putNumber("stageOneAngle",stageOneSub.getAngle().getDegrees()); | ||
SmartDashboard.putNumber("stageTwoAngle",stageTwoSub.getAngle().getDegrees()); | ||
|
||
|
||
SmartDashboard.putNumber("ef_x",efPosition[0]); | ||
SmartDashboard.putNumber("ef_y",efPosition[1]); | ||
|
||
|
||
Rotation2d[] calculatedArmAngles = calculateArmAngles(efPosition[0],efPosition[1]); | ||
|
||
SmartDashboard.putNumber("stageOneRad_calculated",calculatedArmAngles[0].getDegrees()); | ||
SmartDashboard.putNumber("stageTwoRad_calculated",calculatedArmAngles[1].getDegrees()); | ||
|
||
|
||
|
||
|
||
// stageOneSub.setAngle(Rotation2d.fromDegrees(SmartDashboard.getNumber("stageOneRef",70))); | ||
// stageTwoSub.setAngle(Rotation2d.fromDegrees(SmartDashboard.getNumber("stageTwoRef",15))); | ||
|
||
stageOneSub.setAngle(Rotation2d.fromDegrees(90)); | ||
stageTwoSub.setAngle(Rotation2d.fromDegrees(15)); | ||
|
||
|
||
} | ||
} |
138 changes: 138 additions & 0 deletions
138
src/main/java/frc/robot/subsystems/arm/StageOneSub.java
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 |
---|---|---|
@@ -0,0 +1,138 @@ | ||
// 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 frc.robot.subsystems.arm; | ||
|
||
import com.ctre.phoenix.motorcontrol.*; | ||
import com.ctre.phoenix.motorcontrol.can.TalonSRX; | ||
import edu.wpi.first.math.geometry.Rotation2d; | ||
import edu.wpi.first.math.util.Units; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
|
||
import static frc.robot.Constants.ArmConstants.*; | ||
|
||
public class StageOneSub extends SubsystemBase { | ||
/** Creates a new StageOneSub. */ | ||
|
||
TalonSRX primary; | ||
TalonSRX secondary; | ||
|
||
|
||
public StageOneSub() { | ||
primary = new TalonSRX(stageOneRightId); | ||
secondary = new TalonSRX(stageOneLeftId); | ||
|
||
primary.configFactoryDefault(1000); | ||
secondary.configFactoryDefault(1000); | ||
|
||
primary.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Absolute,0,1000); | ||
primary.configFeedbackNotContinuous(false,1000); | ||
|
||
primary.setNeutralMode(NeutralMode.Coast); | ||
secondary.setNeutralMode(NeutralMode.Coast); | ||
|
||
|
||
primary.configVoltageCompSaturation(12.0,1000); | ||
primary.enableVoltageCompensation(true); | ||
secondary.configVoltageCompSaturation(12.0,1000); | ||
secondary.enableVoltageCompensation(true); | ||
|
||
primary.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true,continuousCurrentLimit,peakCurrentLimit,peakCurrentTime),1000); | ||
secondary.configSupplyCurrentLimit(new SupplyCurrentLimitConfiguration(true,continuousCurrentLimit,peakCurrentLimit,peakCurrentTime),1000); | ||
|
||
|
||
primary.setSensorPhase(false); | ||
primary.setInverted(true); | ||
|
||
secondary.follow(primary); | ||
secondary.setInverted(InvertType.OpposeMaster); | ||
|
||
primary.configForwardSoftLimitThreshold((int)radToNativeSensorPosition(Units.degreesToRadians(95)),1000); | ||
primary.configReverseSoftLimitThreshold((int)radToNativeSensorPosition(Units.degreesToRadians(35)),1000); | ||
primary.configForwardSoftLimitEnable(true,1000); | ||
primary.configReverseSoftLimitEnable(true); | ||
|
||
|
||
// primary.configNominalOutputForward(0.05,1000); | ||
// primary.configNominalOutputReverse(-0.05,1000); | ||
|
||
primary.configPeakOutputForward(0.7,1000); | ||
primary.configPeakOutputReverse(-0.7,1000); | ||
|
||
|
||
|
||
primary.config_kP(0,stageOnekP,1000); | ||
primary.config_kI(0,stageOnekI,1000); | ||
primary.config_kD(0,stageOnekD,1000); | ||
// primary.config_kF(0,stageOnekF,1000); | ||
|
||
|
||
|
||
|
||
|
||
} | ||
|
||
@Override | ||
public void periodic() { | ||
// This method will be called once per scheduler run | ||
// SmartDashboard.putNumber("stageOneAngle",getAngle().getDegrees()); | ||
|
||
// SmartDashboard.putNumber("rawSensor",primary.getSelectedSensorPosition()); | ||
// SmartDashboard.putNumber("convertedSensor", radToNativeSensorPosition(nativeSensorPositionToRad(primary.getSelectedSensorPosition()))); | ||
|
||
// SmartDashboard.putNumber("stageOneOutput",primary.getMotorOutputPercent()); | ||
|
||
|
||
|
||
} | ||
|
||
public void setPercentOutput(double output){ | ||
// if(output>0.5)output = 0.5; | ||
// if(output<-0.5)output = -0.5; | ||
primary.set(ControlMode.PercentOutput,output); | ||
} | ||
|
||
public void setAngle(Rotation2d angle) { | ||
primary.set(ControlMode.Position,radToNativeSensorPosition(angle.getRadians())); | ||
} | ||
|
||
public Rotation2d getAngle(){ //gets angle from horizontal | ||
|
||
double angleRad = nativeSensorPositionToRad(primary.getSelectedSensorPosition()); | ||
|
||
return Rotation2d.fromRadians(angleRad); | ||
} | ||
|
||
public double nativeSensorPositionToRad(double sensorReading){ | ||
sensorReading *= stageOneEncoderTicksToRadians; | ||
|
||
sensorReading = (2*Math.PI) + sensorReading; | ||
|
||
if(sensorReading>Math.PI) | ||
sensorReading = sensorReading - 2*Math.PI; | ||
|
||
sensorReading+= Units.degreesToRadians(22.5); | ||
return sensorReading; | ||
} | ||
|
||
public double radToNativeSensorPosition(double angleRad) { | ||
|
||
angleRad -= Units.degreesToRadians(22.5); | ||
|
||
|
||
if (angleRad < -Math.PI) | ||
angleRad += 2 * Math.PI; | ||
|
||
angleRad -= 2 * Math.PI; | ||
|
||
angleRad /= stageOneEncoderTicksToRadians; | ||
|
||
|
||
return angleRad; | ||
} | ||
|
||
|
||
|
||
} |
Oops, something went wrong.