[wpiunits] Add subproject for a Java typesafe unit system (#5371)
# Background
Unit safety has always been a problem in WPILib. Any value corresponding to a physical measurement, such as current draw or distance traveled, is represented by a bare number with no unit tied to it; it's up to the programmer to know what units they're working and take care to remember that while working on their robot program. This leads to bugs when programmers accidentally mix units without knowing, or measure something (such as a wheel diameter) in one unit and program using another. `wpiunits` is intended to eliminate that class of bugs.
Another source of friction is the controllers and models in `wpimath` that expect all inputs to be in terms of SI units (meter, kilogram, and so on), while most FRC teams are US-based and most commonly use imperial units. wpimath does a good job of noting unit types in method names and argument names; however, it still relies on users properly converting values (and knowing they even have to do so).
# API
There are really only two core classes in this library: `Unit` and `Measure`. A `Unit` represents some dimension like distance or time. `Unit` is subclassed to define specific dimensions (eg `Distance` and `Time`) and those subclasses are instantiated to defined particular units in those dimensions, such as `Meters` and `Feet` being instances of the `Distance` class.
A `Measure` is a value tied to a particular dimension like distance and knows what unit that value is tied to. `Measure` has two implementations - one immutable and one mutable. The `Measure` interface only defines *read-only* operations; any API working with measurements should use the interface. The default implementation is `ImmutableMeasure`, which only implements those read-only operations and is useful for tracking constants. `MutableMeasure` also adds some methods that will allow for mutation of its internal state; this class is intended for use for things like sensors and controllers that track internal state and don't want to allocate new `Measure` objects every time something like `myEncoder.getDistance()` is called. However, the APIs for those methods should still only expose the read-only `Measure` interface so users can't (without casting or reflection) change the internal values.
A `Units` class provides convenient definitions for most of the commonly used unit types, such as `Meters`, `Feet`, and `Milliseconds`. I recommend static importing these units eg `import static edu.wpi.first.units.Units.Meters`) so they can be used like `Meters.of(1.234)` instead of `Units.Meters.of(1.234)`
# Examples
These examples are admittedly contrived. Users shouldn't be interacting much with measure objects themselves, since wpimath and wpilibj classes will be updated to support working with them; users will often just have to take a `Measure` output from one place (such as an encoder) and feed it as input to something else (such as a PID controller or kinematics model)
```java
// Using raw units
Encoder encoder = ...
int kPulsesPerRev = 2048;
double kWheelDiameterMeters = Units.inchesToMeters(6);
double kGearRatio = 10.86;
// always have to remember this encoder will output in meters!
encoder.setDistancePerPulse(kWheelDiameterMeters * Math.PI / (kGearRatio * kPulsesPerRev));
Command driveDistance(double distance) {
// have to know the distance argument needs to be in meters!
return run(this::driveStraight).until(() -> encoder.getDistance() >= distance);
}
// Oops! This will go 16 feet, not 5!
Command driveFiveFeet = driveDistance(5);
Command driveOneMeter = driveDistance(1);
```
```java
// Using wpiunits
Encoder encoder = ...
int kPulsesPerRev = 2048;
Measure<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> distance) {
// Measure#gte automatically handles unit conversions
return run(this::driveStraight).until(() -> encoder.getDistance().gte(distance));
}
// Users HAVE to be explicit about their units
Command driveFiveFeet = driveDistance(Feet.of(5));
Command driveOneMeter = driveDistance(Meters.of(1));
```
```java
SmartDashboard.putNumber("Temperature (C)", pdp.getTemperature().in(Celsius));
SmartDashboard.putNumber("Temperature (F)", pdp.getTemperature().in(Fahrenheit));
```
```java
var InchSecond = Inch.mult(Second); // new combined unit types can be user-defined
var InchPerSecond = Inch.per(Second);
PIDController<Distance, ElectricPotential> heightController = new PIDController<>(
/* kP */ Volts.of(0.2).per(Inch),
/* kI */ Volts.of(0.002).per(InchSecond),
/* kD */ Volts.of(0.008).per(InchPerSecond)
);
var elevatorTop = Feet.of(4).plus(Inches.of(6.125));
elevatorMotor.setVoltage(heightController.calculate(encoder.getDistance(), elevatorTop));
```
2023-07-23 17:18:17 -04:00
|
|
|
// 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 edu.wpi.first.units;
|
|
|
|
|
|
|
|
|
|
import java.lang.reflect.Constructor;
|
|
|
|
|
import java.lang.reflect.InvocationTargetException;
|
|
|
|
|
import java.util.Objects;
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Builder used for easily deriving new units from existing ones.
|
|
|
|
|
*
|
|
|
|
|
* @param <U> the type of the unit
|
|
|
|
|
*/
|
|
|
|
|
public final class UnitBuilder<U extends Unit<U>> {
|
|
|
|
|
private final U m_base;
|
|
|
|
|
private UnaryFunction m_fromBase;
|
|
|
|
|
private UnaryFunction m_toBase;
|
|
|
|
|
private String m_name;
|
|
|
|
|
private String m_symbol;
|
|
|
|
|
|
2024-01-19 23:42:09 -08:00
|
|
|
/**
|
|
|
|
|
* Creates a new unit builder object, building off of a base unit. The base unit does not have to
|
|
|
|
|
* be <i>the</i> base unit of its unit system; furlongs work just as well here as meters.
|
|
|
|
|
*
|
|
|
|
|
* @param base the unit to base the new unit off of
|
|
|
|
|
*/
|
[wpiunits] Add subproject for a Java typesafe unit system (#5371)
# Background
Unit safety has always been a problem in WPILib. Any value corresponding to a physical measurement, such as current draw or distance traveled, is represented by a bare number with no unit tied to it; it's up to the programmer to know what units they're working and take care to remember that while working on their robot program. This leads to bugs when programmers accidentally mix units without knowing, or measure something (such as a wheel diameter) in one unit and program using another. `wpiunits` is intended to eliminate that class of bugs.
Another source of friction is the controllers and models in `wpimath` that expect all inputs to be in terms of SI units (meter, kilogram, and so on), while most FRC teams are US-based and most commonly use imperial units. wpimath does a good job of noting unit types in method names and argument names; however, it still relies on users properly converting values (and knowing they even have to do so).
# API
There are really only two core classes in this library: `Unit` and `Measure`. A `Unit` represents some dimension like distance or time. `Unit` is subclassed to define specific dimensions (eg `Distance` and `Time`) and those subclasses are instantiated to defined particular units in those dimensions, such as `Meters` and `Feet` being instances of the `Distance` class.
A `Measure` is a value tied to a particular dimension like distance and knows what unit that value is tied to. `Measure` has two implementations - one immutable and one mutable. The `Measure` interface only defines *read-only* operations; any API working with measurements should use the interface. The default implementation is `ImmutableMeasure`, which only implements those read-only operations and is useful for tracking constants. `MutableMeasure` also adds some methods that will allow for mutation of its internal state; this class is intended for use for things like sensors and controllers that track internal state and don't want to allocate new `Measure` objects every time something like `myEncoder.getDistance()` is called. However, the APIs for those methods should still only expose the read-only `Measure` interface so users can't (without casting or reflection) change the internal values.
A `Units` class provides convenient definitions for most of the commonly used unit types, such as `Meters`, `Feet`, and `Milliseconds`. I recommend static importing these units eg `import static edu.wpi.first.units.Units.Meters`) so they can be used like `Meters.of(1.234)` instead of `Units.Meters.of(1.234)`
# Examples
These examples are admittedly contrived. Users shouldn't be interacting much with measure objects themselves, since wpimath and wpilibj classes will be updated to support working with them; users will often just have to take a `Measure` output from one place (such as an encoder) and feed it as input to something else (such as a PID controller or kinematics model)
```java
// Using raw units
Encoder encoder = ...
int kPulsesPerRev = 2048;
double kWheelDiameterMeters = Units.inchesToMeters(6);
double kGearRatio = 10.86;
// always have to remember this encoder will output in meters!
encoder.setDistancePerPulse(kWheelDiameterMeters * Math.PI / (kGearRatio * kPulsesPerRev));
Command driveDistance(double distance) {
// have to know the distance argument needs to be in meters!
return run(this::driveStraight).until(() -> encoder.getDistance() >= distance);
}
// Oops! This will go 16 feet, not 5!
Command driveFiveFeet = driveDistance(5);
Command driveOneMeter = driveDistance(1);
```
```java
// Using wpiunits
Encoder encoder = ...
int kPulsesPerRev = 2048;
Measure<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> distance) {
// Measure#gte automatically handles unit conversions
return run(this::driveStraight).until(() -> encoder.getDistance().gte(distance));
}
// Users HAVE to be explicit about their units
Command driveFiveFeet = driveDistance(Feet.of(5));
Command driveOneMeter = driveDistance(Meters.of(1));
```
```java
SmartDashboard.putNumber("Temperature (C)", pdp.getTemperature().in(Celsius));
SmartDashboard.putNumber("Temperature (F)", pdp.getTemperature().in(Fahrenheit));
```
```java
var InchSecond = Inch.mult(Second); // new combined unit types can be user-defined
var InchPerSecond = Inch.per(Second);
PIDController<Distance, ElectricPotential> heightController = new PIDController<>(
/* kP */ Volts.of(0.2).per(Inch),
/* kI */ Volts.of(0.002).per(InchSecond),
/* kD */ Volts.of(0.008).per(InchPerSecond)
);
var elevatorTop = Feet.of(4).plus(Inches.of(6.125));
elevatorMotor.setVoltage(heightController.calculate(encoder.getDistance(), elevatorTop));
```
2023-07-23 17:18:17 -04:00
|
|
|
public UnitBuilder(U base) {
|
|
|
|
|
this.m_base = Objects.requireNonNull(base, "Base unit cannot be null");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Sets the unit conversions based on a simple offset. The new unit will have its values equal to
|
|
|
|
|
* (base value - offset).
|
|
|
|
|
*
|
|
|
|
|
* @param offset the offset
|
2023-10-20 18:14:14 -07:00
|
|
|
* @return this builder
|
[wpiunits] Add subproject for a Java typesafe unit system (#5371)
# Background
Unit safety has always been a problem in WPILib. Any value corresponding to a physical measurement, such as current draw or distance traveled, is represented by a bare number with no unit tied to it; it's up to the programmer to know what units they're working and take care to remember that while working on their robot program. This leads to bugs when programmers accidentally mix units without knowing, or measure something (such as a wheel diameter) in one unit and program using another. `wpiunits` is intended to eliminate that class of bugs.
Another source of friction is the controllers and models in `wpimath` that expect all inputs to be in terms of SI units (meter, kilogram, and so on), while most FRC teams are US-based and most commonly use imperial units. wpimath does a good job of noting unit types in method names and argument names; however, it still relies on users properly converting values (and knowing they even have to do so).
# API
There are really only two core classes in this library: `Unit` and `Measure`. A `Unit` represents some dimension like distance or time. `Unit` is subclassed to define specific dimensions (eg `Distance` and `Time`) and those subclasses are instantiated to defined particular units in those dimensions, such as `Meters` and `Feet` being instances of the `Distance` class.
A `Measure` is a value tied to a particular dimension like distance and knows what unit that value is tied to. `Measure` has two implementations - one immutable and one mutable. The `Measure` interface only defines *read-only* operations; any API working with measurements should use the interface. The default implementation is `ImmutableMeasure`, which only implements those read-only operations and is useful for tracking constants. `MutableMeasure` also adds some methods that will allow for mutation of its internal state; this class is intended for use for things like sensors and controllers that track internal state and don't want to allocate new `Measure` objects every time something like `myEncoder.getDistance()` is called. However, the APIs for those methods should still only expose the read-only `Measure` interface so users can't (without casting or reflection) change the internal values.
A `Units` class provides convenient definitions for most of the commonly used unit types, such as `Meters`, `Feet`, and `Milliseconds`. I recommend static importing these units eg `import static edu.wpi.first.units.Units.Meters`) so they can be used like `Meters.of(1.234)` instead of `Units.Meters.of(1.234)`
# Examples
These examples are admittedly contrived. Users shouldn't be interacting much with measure objects themselves, since wpimath and wpilibj classes will be updated to support working with them; users will often just have to take a `Measure` output from one place (such as an encoder) and feed it as input to something else (such as a PID controller or kinematics model)
```java
// Using raw units
Encoder encoder = ...
int kPulsesPerRev = 2048;
double kWheelDiameterMeters = Units.inchesToMeters(6);
double kGearRatio = 10.86;
// always have to remember this encoder will output in meters!
encoder.setDistancePerPulse(kWheelDiameterMeters * Math.PI / (kGearRatio * kPulsesPerRev));
Command driveDistance(double distance) {
// have to know the distance argument needs to be in meters!
return run(this::driveStraight).until(() -> encoder.getDistance() >= distance);
}
// Oops! This will go 16 feet, not 5!
Command driveFiveFeet = driveDistance(5);
Command driveOneMeter = driveDistance(1);
```
```java
// Using wpiunits
Encoder encoder = ...
int kPulsesPerRev = 2048;
Measure<Distance> kWheelDiameter = Inches.of(6);
double kGearRatio = 10.86;
encoder.setDistancePerPulse(kWheelDiameter.times(Math.PI).divide(kGearRatio * kPulsesPerRev));
Command driveDistance(Measure<Distance> distance) {
// Measure#gte automatically handles unit conversions
return run(this::driveStraight).until(() -> encoder.getDistance().gte(distance));
}
// Users HAVE to be explicit about their units
Command driveFiveFeet = driveDistance(Feet.of(5));
Command driveOneMeter = driveDistance(Meters.of(1));
```
```java
SmartDashboard.putNumber("Temperature (C)", pdp.getTemperature().in(Celsius));
SmartDashboard.putNumber("Temperature (F)", pdp.getTemperature().in(Fahrenheit));
```
```java
var InchSecond = Inch.mult(Second); // new combined unit types can be user-defined
var InchPerSecond = Inch.per(Second);
PIDController<Distance, ElectricPotential> heightController = new PIDController<>(
/* kP */ Volts.of(0.2).per(Inch),
/* kI */ Volts.of(0.002).per(InchSecond),
/* kD */ Volts.of(0.008).per(InchPerSecond)
);
var elevatorTop = Feet.of(4).plus(Inches.of(6.125));
elevatorMotor.setVoltage(heightController.calculate(encoder.getDistance(), elevatorTop));
```
2023-07-23 17:18:17 -04:00
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> offset(double offset) {
|
|
|
|
|
m_toBase = derivedValue -> derivedValue + offset;
|
|
|
|
|
m_fromBase = baseValue -> baseValue - offset;
|
|
|
|
|
return this;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Maps a value {@code value} in the range {@code [inMin..inMax]} to an output in the range {@code
|
|
|
|
|
* [outMin..outMax]}. Inputs outside the bounds will be mapped correspondingly to outputs outside
|
|
|
|
|
* the output bounds. Inputs equal to {@code inMin} will be mapped to {@code outMin}, and inputs
|
|
|
|
|
* equal to {@code inMax} will similarly be mapped to {@code outMax}.
|
|
|
|
|
*
|
|
|
|
|
* @param value the value to map
|
|
|
|
|
* @param inMin the minimum input value (does not have to be absolute)
|
|
|
|
|
* @param inMax the maximum input value (does not have to be absolute)
|
|
|
|
|
* @param outMin the minimum output value (does not have to be absolute)
|
|
|
|
|
* @param outMax the maximum output value (does not have to be absolute)
|
|
|
|
|
* @return the mapped output
|
|
|
|
|
*/
|
|
|
|
|
// NOTE: This method lives here instead of in MappingBuilder because inner classes can't
|
|
|
|
|
// define static methods prior to Java 16.
|
|
|
|
|
private static double mapValue(
|
|
|
|
|
double value, double inMin, double inMax, double outMin, double outMax) {
|
|
|
|
|
return (value - inMin) * (outMax - outMin) / (inMax - inMin) + outMin;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/** Helper class used for safely chaining mapping builder calls. */
|
|
|
|
|
public class MappingBuilder {
|
|
|
|
|
private final double m_minInput;
|
|
|
|
|
private final double m_maxInput;
|
|
|
|
|
|
|
|
|
|
private MappingBuilder(double minInput, double maxInput) {
|
|
|
|
|
this.m_minInput = minInput;
|
|
|
|
|
this.m_maxInput = maxInput;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Finalizes the mapping by defining the output range.
|
|
|
|
|
*
|
|
|
|
|
* @param minOutput the minimum output value (does not have to be absolute)
|
|
|
|
|
* @param maxOutput the maximum output value (does not have to be absolute)
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> toOutputRange(double minOutput, double maxOutput) {
|
|
|
|
|
UnitBuilder.this.m_fromBase = x -> mapValue(x, m_minInput, m_maxInput, minOutput, maxOutput);
|
|
|
|
|
UnitBuilder.this.m_toBase = y -> mapValue(y, minOutput, maxOutput, m_minInput, m_maxInput);
|
|
|
|
|
return UnitBuilder.this;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Defines a mapping for values within the given input range. This method call should be
|
|
|
|
|
* immediately followed by {@code .toOutputRange}, eg {@code mappingInputRange(1,
|
|
|
|
|
* 2).toOutputRange(3, 4)}, which will return the unit builder for continued chaining.
|
|
|
|
|
*
|
|
|
|
|
* @param minBase the minimum input value (does not have to be absolute)
|
|
|
|
|
* @param maxBase the maximum output value (does not have to be absolute)
|
|
|
|
|
* @return a builder object used to define the output range
|
|
|
|
|
*/
|
|
|
|
|
public MappingBuilder mappingInputRange(double minBase, double maxBase) {
|
|
|
|
|
return new MappingBuilder(minBase, maxBase);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Sets the conversion function to transform values in the base unit to values in the derived
|
|
|
|
|
* unit.
|
|
|
|
|
*
|
|
|
|
|
* @param fromBase the conversion function
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> fromBase(UnaryFunction fromBase) {
|
|
|
|
|
this.m_fromBase = Objects.requireNonNull(fromBase, "fromBase function cannot be null");
|
|
|
|
|
return this;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Sets the conversion function to transform values in the derived unit to values in the base
|
|
|
|
|
* unit.
|
|
|
|
|
*
|
|
|
|
|
* @param toBase the conversion function
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> toBase(UnaryFunction toBase) {
|
|
|
|
|
this.m_toBase = Objects.requireNonNull(toBase, "toBase function cannot be null");
|
|
|
|
|
return this;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Sets the name of the new unit.
|
|
|
|
|
*
|
|
|
|
|
* @param name the new name
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> named(String name) {
|
|
|
|
|
this.m_name = name;
|
|
|
|
|
return this;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Sets the symbol of the new unit.
|
|
|
|
|
*
|
|
|
|
|
* @param symbol the new symbol
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> symbol(String symbol) {
|
|
|
|
|
this.m_symbol = symbol;
|
|
|
|
|
return this;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Helper for defining units that are a scalar fraction of the base unit, such as centimeters
|
|
|
|
|
* being 1/100th of the base unit (meters). The fraction value is specified as the denominator of
|
|
|
|
|
* the fraction, so a centimeter definition would use {@code splitInto(100)} instead of {@code
|
|
|
|
|
* splitInto(1/100.0)}.
|
|
|
|
|
*
|
|
|
|
|
* @param fraction the denominator portion of the fraction of the base unit that a value of 1 in
|
|
|
|
|
* the derived unit corresponds to
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> splitInto(double fraction) {
|
|
|
|
|
if (fraction == 0) {
|
|
|
|
|
throw new IllegalArgumentException("Fraction must be nonzero");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return toBase(x -> x / fraction).fromBase(b -> b * fraction);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Helper for defining units that are a scalar multiple of the base unit, such as kilometers being
|
|
|
|
|
* 1000x of the base unit (meters).
|
|
|
|
|
*
|
|
|
|
|
* @param aggregation the magnitude required for a measure in the base unit to equal a magnitude
|
|
|
|
|
* of 1 in the derived unit
|
|
|
|
|
* @return the unit builder, for continued chaining
|
|
|
|
|
*/
|
|
|
|
|
public UnitBuilder<U> aggregate(double aggregation) {
|
|
|
|
|
if (aggregation == 0) {
|
|
|
|
|
throw new IllegalArgumentException("Aggregation amount must be nonzero");
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
return toBase(x -> x * aggregation).fromBase(b -> b / aggregation);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Creates the new unit based off of the builder methods called prior.
|
|
|
|
|
*
|
|
|
|
|
* @return the new derived unit
|
|
|
|
|
* @throws NullPointerException if the unit conversions, unit name, or unit symbol were not set
|
|
|
|
|
* @throws RuntimeException if the base unit does not define a constructor accepting the
|
|
|
|
|
* conversion functions, unit name, and unit symbol - in that order
|
|
|
|
|
*/
|
|
|
|
|
@SuppressWarnings("PMD.AvoidAccessibilityAlteration")
|
|
|
|
|
public U make() {
|
|
|
|
|
Objects.requireNonNull(m_fromBase, "fromBase function was not set");
|
|
|
|
|
Objects.requireNonNull(m_toBase, "toBase function was not set");
|
|
|
|
|
Objects.requireNonNull(m_name, "new unit name was not set");
|
|
|
|
|
Objects.requireNonNull(m_symbol, "new unit symbol was not set");
|
|
|
|
|
Class<? extends U> baseType = m_base.m_baseType;
|
|
|
|
|
try {
|
|
|
|
|
Constructor<? extends U> ctor =
|
|
|
|
|
baseType.getDeclaredConstructor(
|
|
|
|
|
UnaryFunction.class, // toBaseUnits
|
|
|
|
|
UnaryFunction.class, // fromBaseUnits
|
|
|
|
|
String.class, // name
|
|
|
|
|
String.class); // symbol
|
|
|
|
|
// need to flag the constructor as accessible so we can use private, package-private, and
|
|
|
|
|
// protected constructors
|
|
|
|
|
ctor.setAccessible(true);
|
|
|
|
|
return ctor.newInstance(
|
|
|
|
|
m_toBase.pipeTo(m_base.getConverterToBase()),
|
|
|
|
|
m_base.getConverterFromBase().pipeTo(m_fromBase),
|
|
|
|
|
m_name,
|
|
|
|
|
m_symbol);
|
|
|
|
|
} catch (InstantiationException e) {
|
|
|
|
|
throw new RuntimeException("Could not instantiate class " + baseType.getName(), e);
|
|
|
|
|
} catch (IllegalAccessException e) {
|
|
|
|
|
throw new RuntimeException("Could not access constructor", e);
|
|
|
|
|
} catch (InvocationTargetException e) {
|
|
|
|
|
throw new RuntimeException("Constructing " + baseType.getName() + " raised an exception", e);
|
|
|
|
|
} catch (NoSuchMethodException e) {
|
|
|
|
|
throw new RuntimeException("No compatible constructor", e);
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
}
|