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

use outboard steering control only #542

Merged
merged 1 commit into from
Nov 6, 2024
Merged
Show file tree
Hide file tree
Changes from all 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
4 changes: 0 additions & 4 deletions lib/src/main/java/org/team100/lib/experiments/Experiment.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,6 @@ public enum Experiment {
* Filter rotational output to remove oscillation
*/
UseThetaFilter,
/**
* Use outboard closed-loop position control for steering instead of onboard PID
*/
OutboardSteering,
/**
* Use low-pass filter and deadbanding on controller feedback, to prevent
* overresponse to noise and jitter around zero.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
import org.team100.lib.encoder.EncoderDrive;
import org.team100.lib.encoder.RotaryPositionSensor;
import org.team100.lib.encoder.Talon6Encoder;
import org.team100.lib.framework.TimedRobot100;
import org.team100.lib.logging.LoggerFactory;
import org.team100.lib.motion.drivetrain.kinodynamics.SwerveKinodynamics;
import org.team100.lib.motion.mechanism.LinearMechanism;
Expand All @@ -18,16 +17,13 @@
import org.team100.lib.motion.mechanism.SimpleRotaryMechanism;
import org.team100.lib.motion.servo.AngularPositionServo;
import org.team100.lib.motion.servo.LinearVelocityServo;
import org.team100.lib.motion.servo.OnboardAngularPositionServo;
import org.team100.lib.motion.servo.OutboardAngularPositionServo;
import org.team100.lib.motion.servo.OutboardLinearVelocityServo;
import org.team100.lib.motor.Falcon6Motor;
import org.team100.lib.motor.Kraken6Motor;
import org.team100.lib.motor.MotorPhase;
import org.team100.lib.profile.Profile100;

import edu.wpi.first.math.controller.PIDController;

public class WCPSwerveModule100 extends SwerveModule100 {
private static final double kSteeringSupplyLimit = 10;
private static final double kSteeringStatorLimit = 20;
Expand Down Expand Up @@ -77,10 +73,7 @@ public static WCPSwerveModule100 getKrakenDrive(
SwerveKinodynamics kinodynamics,
EncoderDrive drive,
MotorPhase motorPhase) {
//
// note the outboard steering setting!
//
final boolean useOutboardSteering = true;

LinearVelocityServo driveServo = driveKrakenServo(
parent.child("Drive"),
supplyLimitAmps,
Expand All @@ -96,8 +89,7 @@ public static WCPSwerveModule100 getKrakenDrive(
kSteeringRatio,
kinodynamics,
drive,
motorPhase,
useOutboardSteering);
motorPhase);

return new WCPSwerveModule100(driveServo, turningServo);
}
Expand All @@ -118,10 +110,6 @@ public static WCPSwerveModule100 getFalconDrive(
SwerveKinodynamics kinodynamics,
EncoderDrive drive,
MotorPhase motorPhase) {
//
// note the outboard steering setting!
//
final boolean useOutboardSteering = true;
LinearVelocityServo driveServo = driveFalconServo(
parent.child("Drive"),
supplyLimitAmps,
Expand All @@ -137,8 +125,7 @@ public static WCPSwerveModule100 getFalconDrive(
kSteeringRatio,
kinodynamics,
drive,
motorPhase,
useOutboardSteering);
motorPhase);
return new WCPSwerveModule100(driveServo, turningServo);
}

Expand Down Expand Up @@ -204,21 +191,12 @@ private static AngularPositionServo turningServo(
double gearRatio,
SwerveKinodynamics kinodynamics,
EncoderDrive drive,
MotorPhase motorPhase,
boolean useOutboardSteering) {
MotorPhase motorPhase) {

PIDConstants lowLevelPID = null;
if (useOutboardSteering) {
// Talon outboard POSITION PID
// 10/2/24 drive torque produces about a 0.5 degree deviation so maybe
// this is too low.
lowLevelPID = new PIDConstants(10.0, 0.0, 0.0);
} else {
// These parameters are handed to Talon outboard VELOCITY PID
// this seems more likely to oscillate
// this is tuned in air, not on carpet, so it's probably too soft.
lowLevelPID = new PIDConstants(0.3, 0.0, 0.0);
}
// Talon outboard POSITION PID
// 10/2/24 drive torque produces about a 0.5 degree deviation so maybe
// this is too low.
PIDConstants lowLevelPID = new PIDConstants(10.0, 0.0, 0.0);

// java uses this to calculate feedforward voltages from target velocities etc
Feedforward100 ff = Feedforward100.makeWCPSwerveTurningFalcon6();
Expand Down Expand Up @@ -251,19 +229,8 @@ private static AngularPositionServo turningServo(
builtInEncoder,
gearRatio);

if (useOutboardSteering) {
AngularPositionServo turningServo = getOutboard(
parent,
turningEncoder,
profile,
mech);
turningServo.reset();
return turningServo;
}

AngularPositionServo turningServo = getOnboard(
AngularPositionServo turningServo = getOutboard(
parent,
kinodynamics,
turningEncoder,
profile,
mech);
Expand All @@ -288,31 +255,6 @@ private static AngularPositionServo getOutboard(
return servo;
}

private static AngularPositionServo getOnboard(
LoggerFactory parent,
SwerveKinodynamics kinodynamics,
RotaryPositionSensor turningEncoder,
Profile100 profile,
RotaryMechanism mech) {
// This is the top-level position controller
// this is tuned in air, not on carpet, so it's probably too soft.
PIDController onboardPositionController = new PIDController(
20, // kP
0, // kI
0, // kD
TimedRobot100.LOOP_PERIOD_S);
onboardPositionController.enableContinuousInput(-Math.PI, Math.PI);
onboardPositionController.setTolerance(0.02, 0.02);
AngularPositionServo servo = new OnboardAngularPositionServo(
parent,
mech,
turningEncoder,
kinodynamics.getMaxSteeringVelocityRad_S(),
onboardPositionController);
servo.setProfile(profile);
return servo;
}

private static RotaryPositionSensor turningEncoder(
Class<? extends RotaryPositionSensor> encoderClass,
LoggerFactory parent,
Expand All @@ -334,7 +276,6 @@ private static RotaryPositionSensor turningEncoder(
drive);
}
throw new IllegalArgumentException("unknown encoder class: " + encoderClass.getName());

}

private WCPSwerveModule100(
Expand Down
Loading