2023-01-20 18:06:53 -07:00
|
|
|
package frc4388.robot.subsystems;
|
|
|
|
|
|
2023-02-09 19:13:55 -07:00
|
|
|
import com.ctre.phoenix.motorcontrol.ControlMode;
|
2023-02-28 17:47:35 -07:00
|
|
|
import com.ctre.phoenix.motorcontrol.FeedbackDevice;
|
|
|
|
|
import com.ctre.phoenix.motorcontrol.RemoteSensorSource;
|
|
|
|
|
import com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration;
|
2023-01-20 18:06:53 -07:00
|
|
|
import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
|
2023-02-28 17:47:35 -07:00
|
|
|
import com.ctre.phoenix.sensors.CANCoder;
|
|
|
|
|
import com.ctre.phoenix.sensors.CANCoderConfiguration;
|
2023-02-09 19:13:55 -07:00
|
|
|
import frc4388.robot.Constants.ArmConstants;
|
|
|
|
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
2023-01-20 18:06:53 -07:00
|
|
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
|
|
|
|
|
|
|
|
|
public class Arm extends SubsystemBase {
|
2023-02-09 19:13:55 -07:00
|
|
|
private WPI_TalonFX m_tele;
|
|
|
|
|
private WPI_TalonFX m_pivot;
|
2023-02-28 17:47:35 -07:00
|
|
|
private CANCoder m_pivotEncoder;
|
|
|
|
|
private boolean m_debug;
|
2023-02-13 18:12:32 -07:00
|
|
|
|
|
|
|
|
// Moves arm to distance [dist] then returns new ang
|
2023-02-28 17:47:35 -07:00
|
|
|
public Arm(WPI_TalonFX pivot, WPI_TalonFX tele, CANCoder encoder, boolean debug) {
|
|
|
|
|
m_tele = tele;
|
|
|
|
|
m_pivot = pivot;
|
|
|
|
|
m_pivotEncoder = encoder;
|
|
|
|
|
|
|
|
|
|
TalonFXConfiguration pivotConfig = new TalonFXConfiguration();
|
|
|
|
|
pivotConfig.slot0.kP = ArmConstants.kP;
|
|
|
|
|
pivotConfig.slot0.kI = ArmConstants.kI;
|
|
|
|
|
pivotConfig.slot0.kD = ArmConstants.kD;
|
|
|
|
|
|
|
|
|
|
pivotConfig.remoteFilter0.remoteSensorDeviceID = encoder.getDeviceID();
|
|
|
|
|
pivotConfig.remoteFilter0.remoteSensorSource = RemoteSensorSource.CANCoder;
|
|
|
|
|
pivotConfig.primaryPID.selectedFeedbackSensor = FeedbackDevice.RemoteSensor0;
|
|
|
|
|
pivot.configAllSettings(pivotConfig);
|
|
|
|
|
|
2023-03-02 16:56:37 -07:00
|
|
|
pivot.configForwardSoftLimitThreshold(ArmConstants.TELE_FORWARD_SOFT_LIMIT);
|
|
|
|
|
pivot.configReverseSoftLimitThreshold(ArmConstants.TELE_REVERSE_SOFT_LIMIT);
|
|
|
|
|
pivot.configForwardSoftLimitEnable(true);
|
|
|
|
|
pivot.configReverseSoftLimitEnable(true);
|
|
|
|
|
|
2023-02-28 17:47:35 -07:00
|
|
|
CANCoderConfiguration config = new CANCoderConfiguration();
|
|
|
|
|
config.magnetOffsetDegrees = ArmConstants.OFFSET;
|
|
|
|
|
m_pivotEncoder.configAllSettings(config);
|
2023-02-13 18:12:32 -07:00
|
|
|
|
|
|
|
|
tele.configFactoryDefault();
|
|
|
|
|
pivot.configFactoryDefault();
|
2023-02-09 19:13:55 -07:00
|
|
|
}
|
|
|
|
|
|
2023-02-28 17:47:35 -07:00
|
|
|
public Arm(WPI_TalonFX pivot, WPI_TalonFX tele, CANCoder encoder) {
|
|
|
|
|
this(pivot, tele, encoder, false);
|
2023-02-09 19:13:55 -07:00
|
|
|
}
|
|
|
|
|
|
2023-03-01 16:45:57 -07:00
|
|
|
public void setRotVel(double vel) {
|
2023-03-02 16:56:37 -07:00
|
|
|
m_pivot.set(ControlMode.PercentOutput, vel / 5);
|
2023-03-01 16:45:57 -07:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void setTeleVel(double vel) {
|
2023-03-02 16:56:37 -07:00
|
|
|
m_tele.set(ControlMode.PercentOutput, vel);
|
2023-03-01 16:45:57 -07:00
|
|
|
}
|
|
|
|
|
|
2023-02-09 19:13:55 -07:00
|
|
|
public void armSetRotation(double rot) {
|
|
|
|
|
if (rot > 1 || rot < 0) return;
|
|
|
|
|
// Move arm code
|
2023-02-13 19:16:23 -07:00
|
|
|
m_pivot.set(ControlMode.Position, rot * Math.abs(ArmConstants.PIVOT_REVERSE_SOFT_LIMIT - ArmConstants.PIVOT_FORWARD_SOFT_LIMIT) +
|
2023-02-09 19:13:55 -07:00
|
|
|
ArmConstants.PIVOT_FORWARD_SOFT_LIMIT);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public void armSetLength(double len) {
|
|
|
|
|
if (len > 1 || len < 0) return;
|
|
|
|
|
// Move arm code
|
2023-02-13 19:16:23 -07:00
|
|
|
m_tele.set(ControlMode.Position, len * Math.abs(ArmConstants.TELE_REVERSE_SOFT_LIMIT - ArmConstants.TELE_FORWARD_SOFT_LIMIT) +
|
2023-02-09 19:13:55 -07:00
|
|
|
ArmConstants.TELE_FORWARD_SOFT_LIMIT);
|
2023-02-28 17:47:35 -07:00
|
|
|
|
|
|
|
|
if (m_tele.isRevLimitSwitchClosed() == 1) {
|
|
|
|
|
m_tele.setSelectedSensorPosition(ArmConstants.TELE_REVERSE_SOFT_LIMIT);
|
|
|
|
|
} else if (m_tele.isFwdLimitSwitchClosed() == 1) {
|
|
|
|
|
m_tele.setSelectedSensorPosition(ArmConstants.TELE_FORWARD_SOFT_LIMIT);
|
|
|
|
|
}
|
2023-02-09 19:13:55 -07:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
public double getArmLength() {
|
|
|
|
|
return (m_tele.getSelectedSensorPosition() - ArmConstants.TELE_FORWARD_SOFT_LIMIT) /
|
|
|
|
|
(ArmConstants.TELE_REVERSE_SOFT_LIMIT - ArmConstants.TELE_FORWARD_SOFT_LIMIT);
|
|
|
|
|
}
|
|
|
|
|
|
2023-03-01 16:45:57 -07:00
|
|
|
public double getArmRotation() {
|
|
|
|
|
return (m_pivotEncoder.getAbsolutePosition() - ArmConstants.PIVOT_FORWARD_SOFT_LIMIT) /
|
|
|
|
|
(ArmConstants.PIVOT_REVERSE_SOFT_LIMIT - ArmConstants.PIVOT_FORWARD_SOFT_LIMIT);
|
|
|
|
|
}
|
|
|
|
|
|
2023-02-09 19:13:55 -07:00
|
|
|
public void runPivotTele(double pivot, double tele) {
|
2023-03-02 16:56:37 -07:00
|
|
|
double rot = 0;
|
2023-02-09 19:13:55 -07:00
|
|
|
|
|
|
|
|
if (checkLimits(tele, rot)) {
|
|
|
|
|
armSetRotation(pivot);
|
|
|
|
|
armSetLength(tele);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Checks that an input is within bounds
|
|
|
|
|
* @param _len length from 0 to 1
|
|
|
|
|
* @param _theta radians from the zero (straight up)
|
|
|
|
|
* @return
|
|
|
|
|
*/
|
|
|
|
|
public static boolean checkLimits(double _len, double _theta) {
|
|
|
|
|
var len = _len * (ArmConstants.MAX_ARM_LEN - ArmConstants.MIN_ARM_LEN) + ArmConstants.MIN_ARM_LEN;
|
|
|
|
|
var x = len * Math.cos(_theta);
|
|
|
|
|
var y = ArmConstants.ARM_HEIGHT + len * Math.sin(_theta);
|
|
|
|
|
|
|
|
|
|
var minHeight = Math.pow(ArmConstants.CURVE_POWER, Math.abs(x));
|
|
|
|
|
if (y < minHeight)
|
|
|
|
|
return false;
|
|
|
|
|
|
|
|
|
|
return true;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@Override
|
|
|
|
|
public void periodic() {
|
2023-03-02 16:56:37 -07:00
|
|
|
// if (m_debug)
|
|
|
|
|
// SmartDashboard.putNumber("Arm Motor", m_tele.getSelectedSensorPosition());
|
|
|
|
|
SmartDashboard.putNumber("Pivot AbsPos", m_pivotEncoder.getAbsolutePosition());
|
2023-02-09 19:13:55 -07:00
|
|
|
}
|
2023-01-20 18:06:53 -07:00
|
|
|
}
|