Compare commits
4 Commits
2025-2-1-s
...
ce7246114f
| Author | SHA1 | Date | |
|---|---|---|---|
| ce7246114f | |||
| 198d105741 | |||
| 4d9aa82520 | |||
| c1dddcace5 |
@@ -86,7 +86,7 @@ public class RobotContainer {
|
||||
);
|
||||
|
||||
elevator.setDefaultCommand(
|
||||
elevator.runElevator(operator::getLeftY)
|
||||
elevator.runAssistedElevator(operator::getLeftY)
|
||||
);
|
||||
|
||||
indexer.setDefaultCommand(
|
||||
@@ -222,4 +222,14 @@ public class RobotContainer {
|
||||
() -> elevatorFirst
|
||||
);
|
||||
}
|
||||
|
||||
/*
|
||||
* A moveManipulator method that will guarantee a safe movement.
|
||||
* Here in case we need want to skip moveManipulator debugging
|
||||
*/
|
||||
@SuppressWarnings("unused")
|
||||
private Command safeMoveManipulator(double elevatorPosition, double armPosition) {
|
||||
return moveManipulatorUtil(elevatorPosition, ArmConstants.kArmSafeStowPosition, false, true)
|
||||
.andThen(arm.goToSetpoint(armPosition, 2));
|
||||
}
|
||||
}
|
||||
@@ -1,15 +1,37 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
import static edu.wpi.first.units.Units.Seconds;
|
||||
|
||||
import com.ctre.phoenix6.configs.CANcoderConfiguration;
|
||||
import com.ctre.phoenix6.signals.SensorDirectionValue;
|
||||
import com.revrobotics.spark.config.SparkMaxConfig;
|
||||
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
|
||||
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config;
|
||||
|
||||
public class ArmConstants {
|
||||
public static final int kArmMotorID = 0;
|
||||
public static final int kCANcoderID = 0;
|
||||
|
||||
public static final double kEncoderConversionFactor = 0;
|
||||
public static final int kMotorAmpsMax = 0;
|
||||
|
||||
public static final double kArmMaxVelocity = 0;
|
||||
|
||||
public static final double kPositionalP = 0;
|
||||
public static final double kPositionalI = 0;
|
||||
public static final double kPositionalD = 0;
|
||||
public static final double kPositionalTolerance = Units.degreesToRadians(1);
|
||||
|
||||
public static final double kVelocityP = 0;
|
||||
public static final double kVelocityI = 0;
|
||||
public static final double kVelocityD = 0;
|
||||
// TODO Is this reasonable?
|
||||
public static final double kVelocityTolerance = Units.degreesToRadians(3) / 60;
|
||||
|
||||
public static final double kArmCoralIntakePosition = 0;
|
||||
public static final double kArmL1Position = 0;
|
||||
public static final double kArmL2Position = 0;
|
||||
@@ -19,7 +41,39 @@ public class ArmConstants {
|
||||
public static final double kArmL3AlgaePosition = 0;
|
||||
public static final double kArmSafeStowPosition = 0;
|
||||
|
||||
public static final double kMagnetOffset = 0.0;
|
||||
public static final double kAbsoluteSensorDiscontinuityPoint = 0.0;
|
||||
|
||||
public static final double kSysIDRampRate = 1;
|
||||
public static final double kSysIDStepVolts = 7;
|
||||
public static final double kSysIDTimeout = 10;
|
||||
|
||||
public static final SensorDirectionValue kSensorDirection = SensorDirectionValue.CounterClockwise_Positive;
|
||||
|
||||
public static final IdleMode kIdleMode = IdleMode.kBrake;
|
||||
|
||||
// YOU SHOULDN'T NEED TO CHANGE ANYTHING BELOW THIS LINE UNLESS YOU'RE ADDING A NEW CONFIG
|
||||
|
||||
public static final SysIdRoutine.Config kSysIDConfig = new Config(
|
||||
Volts.of(kSysIDRampRate).per(Second),
|
||||
Volts.of(kSysIDStepVolts),
|
||||
Seconds.of(kSysIDTimeout)
|
||||
);
|
||||
|
||||
public static final CANcoderConfiguration canCoderConfig = new CANcoderConfiguration();
|
||||
|
||||
public static final SparkMaxConfig motorConfig = new SparkMaxConfig();
|
||||
|
||||
static {
|
||||
canCoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.CounterClockwise_Positive;
|
||||
canCoderConfig.MagnetSensor.MagnetOffset = 0.0;
|
||||
// TODO Need to do more reading on this setting, and how to properly offset the Arm so that horizontal is 0
|
||||
//canCoderConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = 0.5;
|
||||
|
||||
motorConfig
|
||||
.smartCurrentLimit(kMotorAmpsMax)
|
||||
.idleMode(kIdleMode);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -43,6 +43,7 @@ public class ElevatorConstants {
|
||||
public static final double kElevatorL2AlgaePosition = 0;
|
||||
public static final double kElevatorL3AlgaePosition = 0;
|
||||
public static final double kElevatorBracePosition = 0;
|
||||
public static final double kElevatorMaxHeight = 0;
|
||||
|
||||
// 1, 7, 10 are the defaults for these, change as necessary
|
||||
public static final double kSysIDRampRate = 1;
|
||||
|
||||
@@ -4,6 +4,8 @@ import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.ctre.phoenix6.hardware.CANcoder;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkBase.PersistMode;
|
||||
import com.revrobotics.spark.SparkBase.ResetMode;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.math.controller.ArmFeedforward;
|
||||
@@ -14,7 +16,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
|
||||
public class Arm extends SubsystemBase {
|
||||
private SparkMax armMotor;
|
||||
protected SparkMax armMotor;
|
||||
|
||||
private CANcoder canCoder;
|
||||
|
||||
@@ -29,7 +31,28 @@ public class Arm extends SubsystemBase {
|
||||
MotorType.kBrushless
|
||||
);
|
||||
|
||||
armMotor.configure(ArmConstants.motorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
|
||||
|
||||
positionController = new PIDController(
|
||||
ArmConstants.kPositionalP,
|
||||
ArmConstants.kPositionalI,
|
||||
ArmConstants.kPositionalD
|
||||
);
|
||||
|
||||
// TODO: Generate constants for continuous input range based on CANcoder configuration?
|
||||
positionController.enableContinuousInput(Units.degreesToRadians(-180), Units.degreesToRadians(179));
|
||||
positionController.setTolerance(ArmConstants.kPositionalTolerance);
|
||||
|
||||
velocityController = new PIDController(
|
||||
ArmConstants.kVelocityP,
|
||||
ArmConstants.kVelocityI,
|
||||
ArmConstants.kVelocityD
|
||||
);
|
||||
|
||||
velocityController.setTolerance(ArmConstants.kVelocityTolerance);
|
||||
|
||||
canCoder = new CANcoder(ArmConstants.kCANcoderID);
|
||||
canCoder.getConfigurator().apply(ArmConstants.canCoderConfig);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -85,7 +108,7 @@ public class Arm extends SubsystemBase {
|
||||
}
|
||||
|
||||
public double getEncoderPosition() {
|
||||
return Units.rotationsToRadians(canCoder.getPosition().getValueAsDouble());
|
||||
return Units.rotationsToRadians(canCoder.getAbsolutePosition().getValueAsDouble());
|
||||
}
|
||||
|
||||
public double getEncoderVelocity() {
|
||||
|
||||
@@ -7,6 +7,9 @@ package frc.robot.subsystems;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.studica.frc.AHRS;
|
||||
import com.studica.frc.AHRS.NavXComType;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
@@ -30,7 +33,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
protected MAXSwerveModule m_rearRight;
|
||||
|
||||
// The gyro sensor
|
||||
private ADIS16470_IMU m_gyro;
|
||||
private AHRS ahrs;
|
||||
|
||||
// Odometry class for tracking robot pose
|
||||
private SwerveDriveOdometry m_odometry;
|
||||
@@ -61,11 +64,11 @@ public class Drivetrain extends SubsystemBase {
|
||||
DrivetrainConstants.kBackRightChassisAngularOffset
|
||||
);
|
||||
|
||||
m_gyro = new ADIS16470_IMU();
|
||||
ahrs = new AHRS(NavXComType.kMXP_SPI);
|
||||
|
||||
m_odometry = new SwerveDriveOdometry(
|
||||
DrivetrainConstants.kDriveKinematics,
|
||||
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
|
||||
Rotation2d.fromDegrees(ahrs.getAngle()),
|
||||
new SwerveModulePosition[] {
|
||||
m_frontLeft.getPosition(),
|
||||
m_frontRight.getPosition(),
|
||||
@@ -78,7 +81,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
public void periodic() {
|
||||
// Update the odometry in the periodic block
|
||||
m_odometry.update(
|
||||
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
|
||||
Rotation2d.fromDegrees(getGyroValue()),
|
||||
new SwerveModulePosition[] {
|
||||
m_frontLeft.getPosition(),
|
||||
m_frontRight.getPosition(),
|
||||
@@ -103,7 +106,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
*/
|
||||
public void resetOdometry(Pose2d pose) {
|
||||
m_odometry.resetPosition(
|
||||
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)),
|
||||
Rotation2d.fromDegrees(getGyroValue()),
|
||||
new SwerveModulePosition[] {
|
||||
m_frontLeft.getPosition(),
|
||||
m_frontRight.getPosition(),
|
||||
@@ -144,7 +147,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
var swerveModuleStates = DrivetrainConstants.kDriveKinematics.toSwerveModuleStates(
|
||||
fieldRelative
|
||||
? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered,
|
||||
Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)))
|
||||
Rotation2d.fromDegrees(getGyroValue()))
|
||||
: new ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered));
|
||||
SwerveDriveKinematics.desaturateWheelSpeeds(
|
||||
swerveModuleStates, DrivetrainConstants.kMaxSpeedMetersPerSecond);
|
||||
@@ -194,7 +197,11 @@ public class Drivetrain extends SubsystemBase {
|
||||
|
||||
/** Zeroes the heading of the robot. */
|
||||
public void zeroHeading() {
|
||||
m_gyro.reset();
|
||||
ahrs.reset();;
|
||||
}
|
||||
|
||||
public double getGyroValue() {
|
||||
return ahrs.getAngle() * (DrivetrainConstants.kGyroReversed ? -1 : 1);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -203,7 +210,7 @@ public class Drivetrain extends SubsystemBase {
|
||||
* @return the robot's heading in degrees, from -180 to 180
|
||||
*/
|
||||
public double getHeading() {
|
||||
return Rotation2d.fromDegrees(m_gyro.getAngle(IMUAxis.kZ)).getDegrees();
|
||||
return Rotation2d.fromDegrees(getGyroValue()).getDegrees();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -212,6 +219,6 @@ public class Drivetrain extends SubsystemBase {
|
||||
* @return The turn rate of the robot, in degrees per second
|
||||
*/
|
||||
public double getTurnRate() {
|
||||
return m_gyro.getRate(IMUAxis.kZ) * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
return ahrs.getRate() * (DrivetrainConstants.kGyroReversed ? -1.0 : 1.0);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -97,8 +97,13 @@ public class Elevator extends SubsystemBase {
|
||||
return motionTarget > ElevatorConstants.kElevatorBracePosition;
|
||||
}
|
||||
|
||||
//manual command that keeps ouput speed consistent no matter the direction
|
||||
public Command runElevator(DoubleSupplier speed) {
|
||||
/**
|
||||
* A manual translation command that will move the elevator using a consistent velocity disregarding direction
|
||||
*
|
||||
* @param speed How fast the elevator moves
|
||||
* @return Sets motor voltage to move the elevator relative to the speed parameter
|
||||
*/
|
||||
public Command runAssistedElevator(DoubleSupplier speed) {
|
||||
return run(() -> {
|
||||
double realSpeedTarget = speed.getAsDouble() * ElevatorConstants.kElevatorMaxVelocity;
|
||||
|
||||
@@ -108,11 +113,29 @@ public class Elevator extends SubsystemBase {
|
||||
) + feedForward.calculate(realSpeedTarget);
|
||||
|
||||
elevatorMotor1.setVoltage(voltsOut);
|
||||
}).until(bottomLimitSwitch::get);
|
||||
}).until(
|
||||
() -> bottomLimitSwitch.get() || encoder.getPosition() >= ElevatorConstants.kElevatorMaxHeight);
|
||||
}
|
||||
|
||||
/**
|
||||
* A manual translation command that uses feed forward calculation to maintain position
|
||||
*
|
||||
* @param speed The speed at which the elevator translates
|
||||
* @return Sets motor voltage to translate the elevator and maintain position
|
||||
*/
|
||||
public Command runManualElevator(double speed) {
|
||||
return run(() -> {
|
||||
elevatorMotor1.set(speed);
|
||||
});
|
||||
}
|
||||
|
||||
//go to setpoint command
|
||||
/**
|
||||
* Moves the elevator to a target destination (setpoint)
|
||||
*
|
||||
* @param setpoint Target destination of the subsystem
|
||||
* @param timeout Time to achieve the setpoint before quitting
|
||||
* @return Sets motor voltage to achieve the target destination
|
||||
*/
|
||||
public Command goToSetpoint(double setpoint, double timeout) {
|
||||
return run(() -> {
|
||||
double voltsOut = positionController.calculate(
|
||||
@@ -126,7 +149,21 @@ public class Elevator extends SubsystemBase {
|
||||
).withTimeout(timeout);
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the current encoder position
|
||||
*
|
||||
* @return Current encoder position
|
||||
*/
|
||||
public double getEncoderPosition() {
|
||||
return encoder.getPosition();
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the value of the bottom limit switch on the elevator (false = disabled, true = enabled)
|
||||
*
|
||||
* @return The value of bottomLimitSwitch
|
||||
*/
|
||||
public boolean getBottomLimitSwitch() {
|
||||
return bottomLimitSwitch.get();
|
||||
}
|
||||
}
|
||||
62
src/main/java/frc/robot/subsystems/sysid/ArmSysID.java
Normal file
62
src/main/java/frc/robot/subsystems/sysid/ArmSysID.java
Normal file
@@ -0,0 +1,62 @@
|
||||
package frc.robot.subsystems.sysid;
|
||||
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
import static edu.wpi.first.units.Units.Radians;
|
||||
import static edu.wpi.first.units.Units.RadiansPerSecond;
|
||||
|
||||
import edu.wpi.first.units.measure.MutAngle;
|
||||
import edu.wpi.first.units.measure.MutAngularVelocity;
|
||||
import edu.wpi.first.units.measure.MutVoltage;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
import frc.robot.subsystems.Arm;
|
||||
|
||||
public class ArmSysID extends Arm {
|
||||
private MutVoltage appliedVoltage;
|
||||
|
||||
private MutAngle armPosition;
|
||||
|
||||
private MutAngularVelocity armVelocity;
|
||||
|
||||
private SysIdRoutine routine;
|
||||
|
||||
public ArmSysID() {
|
||||
super();
|
||||
|
||||
appliedVoltage = Volts.mutable(0);
|
||||
|
||||
armPosition = Radians.mutable(0);
|
||||
|
||||
armVelocity = RadiansPerSecond.mutable(0);
|
||||
|
||||
routine = new SysIdRoutine(
|
||||
ArmConstants.kSysIDConfig,
|
||||
new SysIdRoutine.Mechanism(
|
||||
armMotor::setVoltage,
|
||||
(log) -> {
|
||||
log.motor("armMotor")
|
||||
.voltage(appliedVoltage.mut_replace(
|
||||
armMotor.get() * RobotController.getBatteryVoltage(), Volts
|
||||
))
|
||||
.angularPosition(armPosition.mut_replace(
|
||||
getEncoderPosition(), Radians
|
||||
))
|
||||
.angularVelocity(armVelocity.mut_replace(
|
||||
getEncoderVelocity(), RadiansPerSecond
|
||||
));
|
||||
},
|
||||
this
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
|
||||
return routine.quasistatic(direction);
|
||||
}
|
||||
|
||||
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
|
||||
return routine.dynamic(direction);
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user