Skip to content

Commit

Permalink
Merge pull request #2 from FRC-4509-MechBulls/✨arm✨
Browse files Browse the repository at this point in the history
Arm tuned
  • Loading branch information
IsaacThoman authored Oct 4, 2023
2 parents f4f5201 + c0cd8ca commit 0d09942
Show file tree
Hide file tree
Showing 8 changed files with 484 additions and 5 deletions.
57 changes: 55 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,24 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {

public static class AutoConstants {
public static final double translationkP = 4;
public static final double rotationkP = 4;

public static final double maxTranslation = 1;
public static final double maxRotation = 1;

}
public static class OperatorConstants {
public static final int kDriverControllerPort = 0;

public static final double driveExponent = 1.8;
public static final double driveMaxSpeed = 0.5; //5
public static final double driveMaxSpeed = 5; //5
public static final double turnExponent = 1.8;
public static final double turnMaxSpeed = 1; //11
public static final double turnMaxSpeed = 11; //11

public static final double maxDrivePower = 1;


public static final double radFeedClamp = 0.5; //max heading adjustment speed
Expand Down Expand Up @@ -98,9 +109,51 @@ public static final class DriveConstants{
public static final double turningMotorkF = 0.0;


}


public static class ArmConstants {

public static final double stageOnekP = 8;
public static final double stageOnekI = 0.0;
public static final double stageOnekD = 0.0;
public static final double stageOnekF = 0.0;

public static final double stageTwokP = 0.3;
public static final double stageTwokI = 0.001;
public static final double stageTwokD = 2;
public static final double stageTwokF = 0.0;



public static final int stageOneLeftId = 11;
public static final int stageOneRightId = 13;

public static final double continuousCurrentLimit = 20;
public static final double peakCurrentLimit = 40;
public static final double peakCurrentTime = 250;

public static final int stageTwoPrimaryId = 49;
public static final int stageTwoSecondaryId = 48;

public static final int stageTwoSmartCurrentLimit = 40;
public static final double stageTwoSecondaryCurrentLimit = 60;

public static final double magEncoderCountsPerRotation = 4096;//4096
public static final double radiansPerRotation = 2 * Math.PI;

public static final double stageOneEncoderTicksToRadians = (radiansPerRotation/magEncoderCountsPerRotation);

public static final double stageOneEncoderOffset = Units.degreesToRadians(291.9 + 90 - .145);

public static final double stageOneLength = Units.inchesToMeters(28.75);
public static final double[] stageOnePivotCoordinate = {-4.864, 18.66};

public static final double stageTwoLength = Units.inchesToMeters(28.75);
public static final double stageTwoEncoderOffset = Units.degreesToRadians(43.6);//180 - 43.6 //43.6 + 180
public static final double stageTwoEncoderRatio = 1;//32.0/22
}



}
26 changes: 25 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,10 @@

package frc.robot;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.Autos;
Expand All @@ -13,6 +16,9 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.arm.StageOneSub;
import frc.robot.subsystems.arm.StageTwoSub;
import frc.robot.subsystems.drive.SwerveSubsystem;
import frc.robot.subsystems.drive.VisionSubsystem;

Expand All @@ -25,18 +31,36 @@
public class RobotContainer {
// The robot's subsystems and commands are defined here...

XboxController driver = new XboxController(0);
CommandXboxController driver = new CommandXboxController(0);

VisionSubsystem visionSub = new VisionSubsystem();
SwerveSubsystem swerveSubsystem = new SwerveSubsystem(visionSub);
RunCommand drive = new RunCommand(()->swerveSubsystem.joystickDrive(driver.getLeftX(),driver.getLeftY(),driver.getRightX()),swerveSubsystem);




Arm arm = new Arm();


/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {

swerveSubsystem.setDefaultCommand(drive);

driver.a().whileTrue(new RunCommand(()->swerveSubsystem.driveToPose(new Pose2d()),swerveSubsystem));

driver.b().onTrue(new InstantCommand(()->swerveSubsystem.resetOdometry()));

// RunCommand sendArmVoltage = new RunCommand(()-> stageOneSub.setPercentOutput(driver.getLeftTriggerAxis()-driver.getRightTriggerAxis()),stageOneSub);

// RunCommand setArmPosition = new RunCommand(()-> stageOneSub.setAngle(Rotation2d.fromDegrees(45)),stageOneSub);


//driver.a().whileTrue(setArmPosition);

// stageOneSub.setDefaultCommand(sendArmVoltage);

// Configure the trigger bindings
configureBindings();
}
Expand Down
83 changes: 83 additions & 0 deletions src/main/java/frc/robot/subsystems/arm/Arm.java
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 src/main/java/frc/robot/subsystems/arm/StageOneSub.java
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;
}



}
Loading

0 comments on commit 0d09942

Please sign in to comment.