Skip to content
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
136 changes: 111 additions & 25 deletions yams/java/yams/mechanisms/config/ArmConfig.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package yams.mechanisms.config;

import edu.wpi.first.math.Pair;
import edu.wpi.first.units.Units;
import edu.wpi.first.units.measure.Angle;
import edu.wpi.first.units.measure.Distance;
Expand All @@ -23,47 +24,63 @@ public class ArmConfig
/**
* {@link SmartMotorController} for the {@link yams.mechanisms.positional.Arm}
*/
private final SmartMotorController motor;
private Optional<SmartMotorController> motor;
/**
* The network root of the mechanism (Optional).
*/
protected Optional<String> networkTableName = Optional.empty();
protected Optional<String> networkTableName = Optional.empty();
/**
* Telemetry name.
*/
private Optional<String> telemetryName = Optional.empty();
private Optional<String> telemetryName = Optional.empty();
/**
* Telemetry verbosity
*/
private Optional<TelemetryVerbosity> telemetryVerbosity = Optional.empty();
private Optional<TelemetryVerbosity> telemetryVerbosity = Optional.empty();
/**
* Lower Hard Limit for the {@link yams.mechanisms.positional.Arm} to be representing in simulation.
*/
private Optional<Angle> lowerHardLimit = Optional.empty();
private Optional<Angle> lowerHardLimit = Optional.empty();
/**
* Upper hard limit for the {@link yams.mechanisms.positional.Arm} representing in simulation.
*/
private Optional<Angle> upperHardLimit = Optional.empty();
private Optional<Angle> upperHardLimit = Optional.empty();
/**
* {@link yams.mechanisms.positional.Arm} length for simulation.
*/
private Optional<Distance> length = Optional.empty();
private Optional<Distance> length = Optional.empty();
/**
* {@link yams.mechanisms.positional.Arm} mass for simulation.
*/
private Optional<Mass> weight = Optional.empty();
private Optional<Mass> weight = Optional.empty();
/**
* {@link yams.mechanisms.positional.Arm} MOI from CAD software. If not given estimated with length and weight.
*/
private OptionalDouble moi = OptionalDouble.empty();
private OptionalDouble moi = OptionalDouble.empty();
/**
* Sim color value
*/
private Color8Bit simColor = new Color8Bit(Color.kOrange);
private Color8Bit simColor = new Color8Bit(Color.kOrange);
/**
* Mechanism position configuration for the {@link yams.mechanisms.positional.Pivot} (Optional).
*/
private MechanismPositionConfig mechanismPositionConfig = new MechanismPositionConfig();
private MechanismPositionConfig mechanismPositionConfig = new MechanismPositionConfig();
/**
* Horizontal zero of the arm's absolute encoder.
*/
private Optional<Angle> horizantalZero = Optional.empty();
/**
* Starting position of the arms motor controller encoder.
*/
private Optional<Angle> startingPosition = Optional.empty();
/**
* Lower and upper soft limits of the arms closed loop controller. (LowerLimit, UpperLimit)
*/
private Optional<Pair<Angle, Angle>> softLimits = Optional.empty();
/**
* Wrapping angles for the Arm applied to the motor controllers closed loop controller. (Min, Max)
*/
private Optional<Pair<Angle, Angle>> continuousWrapping = Optional.empty();

/**
* Arm Configuration class
Expand All @@ -72,9 +89,73 @@ public class ArmConfig
*/
public ArmConfig(SmartMotorController motorController)
{
motor = motorController;
motor = Optional.of(motorController);
}

/**
* Arm configuration class. Required
*/
public ArmConfig()
{}

/**
* Copy constructor.
*
* @param cfg Configuration to copy from.
*/
private ArmConfig(ArmConfig cfg)
{
motor = cfg.motor;
networkTableName = cfg.networkTableName;
telemetryName = cfg.telemetryName;
telemetryVerbosity = cfg.telemetryVerbosity;
lowerHardLimit = cfg.lowerHardLimit;
upperHardLimit = cfg.upperHardLimit;
length = cfg.length;
weight = cfg.weight;
moi = cfg.moi;
simColor = cfg.simColor;
mechanismPositionConfig = cfg.mechanismPositionConfig;
startingPosition = cfg.startingPosition;
softLimits = cfg.softLimits;
continuousWrapping = cfg.continuousWrapping;
horizantalZero = cfg.horizantalZero;
}

@Override
public ArmConfig clone()
{
return new ArmConfig(this);
}

/**
* Configure the {@link SmartMotorController} for the {@link yams.mechanisms.positional.Arm}
*
* @param motorController Primary {@link SmartMotorController} for the {@link yams.mechanisms.positional.Arm}
* @return {@link ArmConfig} for chaining.
*/
public ArmConfig withSmartMotorController(SmartMotorController motorController)
{
if (motor.isPresent())
{
throw new ArmConfigurationException("Arm already has a SmartMotorController!",
"Cannot set a new one!",
".withSmartMotorController(SmartMotorController)");
}
motor = Optional.of(motorController);
moi.ifPresent(moi -> motorController.getConfig().withMomentOfInertia(moi));
if (length.isPresent() && weight.isPresent() && moi.isEmpty())
{
motorController.getConfig().withMomentOfInertia(length.get(), weight.get());
}
horizantalZero.ifPresent(this::withHorizontalZero);
startingPosition.ifPresent(this::withStartingPosition);
softLimits.ifPresent(limits -> withSoftLimits(limits.getFirst(), limits.getSecond()));
continuousWrapping.ifPresent(wrapping -> withWrapping(wrapping.getFirst(), wrapping.getSecond()));
return this;
}


/**
* Publish the color in sim as this.
*
Expand All @@ -96,7 +177,7 @@ public ArmConfig withSimColor(final Color8Bit simColor)
*/
public ArmConfig withMOI(double MOI)
{
motor.getConfig().withMomentOfInertia(MOI);
motor.ifPresent(motor -> motor.getConfig().withMomentOfInertia(MOI));
this.moi = OptionalDouble.of(MOI);
return this;
}
Expand All @@ -111,7 +192,7 @@ public ArmConfig withLength(Distance distance)
{
if (weight.isPresent() && distance != null)
{
motor.getConfig().withMomentOfInertia(distance, weight.get());
motor.ifPresent(motor -> motor.getConfig().withMomentOfInertia(distance, weight.get()));
}
this.length = Optional.ofNullable(distance);
return this;
Expand All @@ -127,7 +208,7 @@ public ArmConfig withMass(Mass mass)
{
if (length.isPresent() && mass != null)
{
motor.getConfig().withMomentOfInertia(length.get(), mass);
motor.ifPresent(motor -> motor.getConfig().withMomentOfInertia(length.get(), mass));
}
this.weight = Optional.ofNullable(mass);
return this;
Expand Down Expand Up @@ -165,7 +246,7 @@ public ArmConfig withTelemetry(String networkRoot, String telemetryName, Telemet
}

/**
* Set the elevator mechnism position configuration.
* Set the elevator mechanism position configuration.
*
* @param mechanismPositionConfig {@link MechanismPositionConfig} for the {@link yams.mechanisms.positional.Elevator}
* @return {@link PivotConfig} for chaining
Expand All @@ -176,27 +257,30 @@ public ArmConfig withMechanismPositionConfig(MechanismPositionConfig mechanismPo
return this;
}


/**
* Set the horizontal zero of the arm.
* Set the horizontal zero of the arms absolute encoder.
*
* @param horizontalZero Offset of the arm that will make the arm read 0 when horizontal.
* @return {@link ArmConfig} for chaining.
*/
public ArmConfig withHorizontalZero(Angle horizontalZero)
{
motor.getConfig().withExternalEncoderZeroOffset(horizontalZero);
this.horizantalZero = Optional.ofNullable(horizontalZero);
motor.ifPresent(motor -> motor.getConfig().withExternalEncoderZeroOffset(horizontalZero));
return this;
}

/**
* Set the arm starting position.
* Set the arm starting angle of the motor controller encoder.
*
* @param startingPosition Starting position of the arm.
* @return {@link ArmConfig} for chaining
*/
public ArmConfig withStartingPosition(Angle startingPosition)
{
motor.getConfig().withStartingPosition(startingPosition);
this.startingPosition = Optional.ofNullable(startingPosition);
motor.ifPresent(motor -> motor.getConfig().withStartingPosition(startingPosition));
return this;
}

Expand All @@ -209,7 +293,8 @@ public ArmConfig withStartingPosition(Angle startingPosition)
*/
public ArmConfig withSoftLimits(Angle lowerLimit, Angle upperLimit)
{
motor.getConfig().withSoftLimit(lowerLimit, upperLimit);
softLimits = Optional.of(Pair.of(lowerLimit, upperLimit));
motor.ifPresent(motor -> motor.getConfig().withSoftLimit(lowerLimit, upperLimit));
return this;
}

Expand All @@ -223,7 +308,8 @@ public ArmConfig withSoftLimits(Angle lowerLimit, Angle upperLimit)
*/
public ArmConfig withWrapping(Angle min, Angle max)
{
motor.getConfig().withContinuousWrapping(min, max);
continuousWrapping = Optional.of(Pair.of(min, max));
motor.ifPresent(motor -> motor.getConfig().withContinuousWrapping(min, max));
return this;
}

Expand All @@ -248,7 +334,7 @@ public ArmConfig withHardLimit(Angle min, Angle max)
*/
public boolean applyConfig()
{
return motor.applyConfig(motor.getConfig());
return motor.orElseThrow().applyConfig(motor.orElseThrow().getConfig());
}

/**
Expand Down Expand Up @@ -328,7 +414,7 @@ public Optional<String> getTelemetryName()
*/
public Optional<Angle> getStartingAngle()
{
return motor.getConfig().getStartingPosition();
return startingPosition;
}

/**
Expand All @@ -338,7 +424,7 @@ public Optional<Angle> getStartingAngle()
*/
public SmartMotorController getMotor()
{
return motor;
return motor.orElseThrow();
}

/**
Expand Down
77 changes: 67 additions & 10 deletions yams/java/yams/mechanisms/config/DifferentialMechanismConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ public class DifferentialMechanismConfig
/**
* {@link SmartMotorController} for the {@link DifferentialMechanism}
*/
private final SmartMotorController leftMotorController;
private Optional<SmartMotorController> leftMotorController = Optional.empty();
/**
* {@link SmartMotorController} for the {@link DifferentialMechanism}
*/
private final SmartMotorController rightMotorController;
private Optional<SmartMotorController> rightMotorController = Optional.empty();
/**
* The network root of the mechanism (Optional).
*/
Expand Down Expand Up @@ -97,11 +97,68 @@ public class DifferentialMechanismConfig
*/
public DifferentialMechanismConfig(SmartMotorController left, SmartMotorController right)
{
leftMotorController = left;
rightMotorController = right;
leftMotorController = Optional.ofNullable(left);
rightMotorController = Optional.ofNullable(right);
mechanismPositionConfig.withMovementPlane(Plane.XY);
}

/**
* Differential Mechanism configuration class. Required call to
* {@link #withSmartMotorControllers(SmartMotorController, SmartMotorController)} before usage.
*/
public DifferentialMechanismConfig()
{
mechanismPositionConfig.withMovementPlane(Plane.XY);
}

/**
* Copy constructor.
*
* @param cfg Configuration to copy.
*/
private DifferentialMechanismConfig(DifferentialMechanismConfig cfg)
{
this.leftMotorController = cfg.leftMotorController;
this.rightMotorController = cfg.rightMotorController;
this.telemetryName = cfg.telemetryName;
this.telemetryVerbosity = cfg.telemetryVerbosity;
this.twistGearing = cfg.twistGearing;
this.twistAngle = cfg.twistAngle;
this.tiltAngle = cfg.tiltAngle;
this.startingTwistAngle = cfg.startingTwistAngle;
this.startingTiltAngle = cfg.startingTiltAngle;
this.MOI = cfg.MOI;
this.length = cfg.length;
this.simColor = cfg.simColor;
this.mechanismPositionConfig = cfg.mechanismPositionConfig;
this.networkRoot = cfg.networkRoot;
}

@Override
public DifferentialMechanismConfig clone()
{
return new DifferentialMechanismConfig(this);
}

/**
* Add the smart motor controllers to the configuration.
*
* @param left Left {@link SmartMotorController}
* @param right Right {@link SmartMotorController}
* @return {@link DifferentialMechanismConfig} for chaining.
*/
public DifferentialMechanismConfig withSmartMotorControllers(SmartMotorController left, SmartMotorController right)
{
if(leftMotorController.isPresent())
throw new DifferentialMechanismConfigurationException("Left motor controller already defined.","Cannot redefine left motor controller!", ".withSmartMotorControllers");
if(rightMotorController.isPresent())
throw new DifferentialMechanismConfigurationException("Right motor controller already defined.","Cannot redefine right motor controller!", ".withSmartMotorControllers");
leftMotorController = Optional.ofNullable(left);
rightMotorController = Optional.ofNullable(right);
setStartingEncoderPositions();
return this;
}

/**
* Get the twist angle of the {@link DifferentialMechanism} with any additional twist gearing.
*
Expand Down Expand Up @@ -161,8 +218,8 @@ private void setStartingEncoderPositions()
var tilt = startingTiltAngle.get();
var left = getLeftMechanismPosition(tilt, twist);
var right = getRightMechanismPosition(tilt, twist);
leftMotorController.getConfig().withStartingPosition(left);
rightMotorController.getConfig().withStartingPosition(right);
leftMotorController.ifPresent(leftMotorController ->leftMotorController.getConfig().withStartingPosition(left));
rightMotorController.ifPresent(rightMotorController -> rightMotorController.getConfig().withStartingPosition(right));
}
}

Expand Down Expand Up @@ -319,8 +376,8 @@ public DifferentialMechanismConfig withTiltStartingPosition(Angle startingPositi
*/
public boolean applyConfig()
{
return leftMotorController.applyConfig(leftMotorController.getConfig()) && rightMotorController.applyConfig(
rightMotorController.getConfig());
return leftMotorController.orElseThrow().applyConfig(leftMotorController.orElseThrow().getConfig()) &&
rightMotorController.orElseThrow().applyConfig(rightMotorController.orElseThrow().getConfig());
}


Expand Down Expand Up @@ -448,7 +505,7 @@ public Optional<Supplier<Angle>> getTiltAngleSupplier()
*/
public SmartMotorController getLeftMotorController()
{
return leftMotorController;
return leftMotorController.orElseThrow();
}

/**
Expand All @@ -458,7 +515,7 @@ public SmartMotorController getLeftMotorController()
*/
public SmartMotorController getRightMotorController()
{
return rightMotorController;
return rightMotorController.orElseThrow();
}

/**
Expand Down
Loading