Skip to content

Commit

Permalink
Pushed more TalonController methods up into TalonSRX.
Browse files Browse the repository at this point in the history
Also revamped how the input sensors are accessed via TalonSRX; both analog and quadrature encoder inputs are accessible via Gyroscope (since both position and velocity are available), and selecting one for feedback will be reflected in the separate selected input Gyroscope. The trick is that all 3 are available at the same time, although they operate upon different frames and at different rates.
  • Loading branch information
rhauch committed Nov 16, 2015
1 parent 9a59d0e commit 4ee3a49
Show file tree
Hide file tree
Showing 8 changed files with 632 additions and 189 deletions.
35 changes: 33 additions & 2 deletions strongback-testing/src/org/strongback/mock/Mock.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

package org.strongback.mock;

import java.util.concurrent.atomic.AtomicLong;

import org.strongback.components.Fuse;
import org.strongback.components.TalonSRX;
import org.strongback.control.Controller;
Expand All @@ -28,6 +30,8 @@
*/
public class Mock {

private static final AtomicLong CAN_DEVICE_ID_GENERATOR = new AtomicLong();

/**
* Create a mock power panel.
*
Expand Down Expand Up @@ -232,13 +236,34 @@ public static MockMotor runningMotor(double speed) {
return new MockMotor(speed);
}

/**
* Create a stopped mock {@link TalonSRX} motor.
*
* @param deviceId the CAN device ID
* @return the mock TalonSRX motor; never null
*/
public static MockTalonSRX stoppedTalonSRX(int deviceId) {
return runningTalonSRX(deviceId, 0.0);
}

/**
* Create a running mock {@link TalonSRX} motor.
*
* @param deviceId the CAN device ID
* @param speed the initial speed
* @return the mock TalonSRX motor; never null
*/
public static MockTalonSRX runningTalonSRX(int deviceId, double speed) {
return new MockTalonSRX(deviceId, speed);
}

/**
* Create a stopped mock {@link TalonSRX} motor.
*
* @return the mock TalonSRX motor; never null
*/
public static MockTalonSRX stoppedTalonSRX() {
return new MockTalonSRX(0.0);
return stoppedTalonSRX(nextDeviceId());
}

/**
Expand All @@ -248,11 +273,16 @@ public static MockTalonSRX stoppedTalonSRX() {
* @return the mock TalonSRX motor; never null
*/
public static MockTalonSRX runningTalonSRX(double speed) {
return new MockTalonSRX(speed);
return runningTalonSRX(nextDeviceId(), speed);
}

protected static int nextDeviceId() {
return (int)CAN_DEVICE_ID_GENERATOR.getAndIncrement();
}

/**
* Create a mock {@link Controller}.
*
* @return the mock controller; never null
*/
public static MockController controller() {
Expand All @@ -261,6 +291,7 @@ public static MockController controller() {

/**
* Create a mock {@link PIDController}.
*
* @return the mock controller; never null
*/
public static MockPIDController pidController() {
Expand Down
63 changes: 59 additions & 4 deletions strongback-testing/src/org/strongback/mock/MockTalonSRX.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,20 @@
package org.strongback.mock;

import org.strongback.components.Fuse;
import org.strongback.components.Gyroscope;
import org.strongback.components.Switch;
import org.strongback.components.TalonSRX;
import org.strongback.components.TemperatureSensor;
import org.strongback.components.VoltageSensor;

public class MockTalonSRX extends MockMotor implements TalonSRX {

private final MockAngleSensor encoder = new MockAngleSensor();
private static final Gyroscope NO_OP_GYRO = new MockGyroscope();

private final int deviceId;
private final MockGyroscope encoderInput = new MockGyroscope();
private final MockGyroscope analogInput = new MockGyroscope();
private Gyroscope selectedInput = NO_OP_GYRO;
private final MockCurrentSensor current = new MockCurrentSensor();
private final MockVoltageSensor voltage = new MockVoltageSensor();
private final MockVoltageSensor busVoltage = new MockVoltageSensor();
Expand All @@ -37,8 +43,14 @@ public class MockTalonSRX extends MockMotor implements TalonSRX {
private double expiration = 0.1d;
private boolean alive = true;

protected MockTalonSRX(double speed) {
protected MockTalonSRX(int deviceId, double speed) {
super(speed);
this.deviceId = deviceId;
}

@Override
public int getDeviceID() {
return deviceId;
}

@Override
Expand All @@ -48,8 +60,51 @@ public MockTalonSRX setSpeed(double speed) {
}

@Override
public MockAngleSensor getAngleSensor() {
return encoder;
public MockGyroscope getAnalogInput() {
return analogInput;
}

@Override
public MockGyroscope getEncoderInput() {
return encoderInput;
}

@Override
public Gyroscope getSelectedSensor() {
return selectedInput;
}

@Override
public MockTalonSRX reverseSensor(boolean flip) {
return this;
}

@Override
public MockTalonSRX setFeedbackDevice(FeedbackDevice device) {
switch(device) {
case ANALOG_POTENTIOMETER:
case ANALOG_ENCODER:
this.selectedInput = analogInput;
break;
case QUADRATURE_ENCODER:
this.selectedInput = encoderInput;
break;
case ENCODER_FALLING:
case ENCODER_RISING:
selectedInput = NO_OP_GYRO;
break;
}
return this;
}

@Override
public MockTalonSRX setStatusFrameRate(StatusFrameRate frameRate, int periodMillis) {
return this;
}

@Override
public MockTalonSRX setVoltageRampRate(double rampRate) {
return this;
}

@Override
Expand Down
149 changes: 148 additions & 1 deletion strongback/src/org/strongback/components/TalonSRX.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,52 @@ public interface TalonSRX extends LimitedMotor {
public TalonSRX setSpeed(double speed);

/**
* Get the CAN device ID.
*
* @return the device ID.
*/
public int getDeviceID();

/**
* <b>Deprecated.</b> Use {@link #getEncoderInput()} instead.
* <p>
* Get the angle sensor (encoder) hooked up to the Talon SRX motor controller.
*
* @return the angle sensor; never null, but if not hooked up the sensor will always return a meaningless value
* @deprecated Use {@link #getEncoderInput()} instead.
*/
@Deprecated
public default AngleSensor getAngleSensor() {
return getEncoderInput();
}

/**
* Get the current encoder angle and rate, regardless of whether it is the current feedback device.
*
* @return the gyroscope that reads the encoder sensor; or null if the motor was created with no quadrature encoder input
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int)
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int, double)
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int, double, double)
*/
public Gyroscope getEncoderInput();

/**
* Get the current analog angle and rate, regardless of whether it is the current feedback device.
*
* @return the gyroscope that reads the 3.3V analog sensor; or null if the motor was created with no analog input
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int)
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int, double)
* @see org.strongback.hardware.Hardware.Motors#talonSRX(int, double, double)
*/
public Gyroscope getAnalogInput();

/**
* Get the input angle and rate of the current {@link #setFeedbackDevice(FeedbackDevice) feedback device}.
*
* @return the selected input device sensor; never null, but it may return a meaningless value if a sensor is not physically
* wired as an input to the Talon device
*/
public AngleSensor getAngleSensor();
public Gyroscope getSelectedSensor();

/**
* Get the Talon SRX's output current sensor.
Expand Down Expand Up @@ -61,6 +102,36 @@ public interface TalonSRX extends LimitedMotor {
*/
public TemperatureSensor getTemperatureSensor();

/**
* Set the feedback device for this controller.
*
* @param device the feedback device; may not be null
* @return this object so that methods can be chained; never null
* @see #reverseSensor(boolean)
*/
public TalonSRX setFeedbackDevice(FeedbackDevice device);

/**
* Set the status frame rate for this controller.
*
* @param frameRate the status frame rate; may not be null
* @param periodMillis frame rate period in milliseconds
* @return this object so that methods can be chained; never null
*/
public TalonSRX setStatusFrameRate(StatusFrameRate frameRate, int periodMillis);

/**
* Flips the sign (multiplies by negative one) the {@link #setFeedbackDevice(FeedbackDevice) feedback device} values read by
* the Talon.
* <p>
* This only affects position and velocity closed loop control. Allows for situations where you may have a sensor flipped
* and going in the wrong direction.
*
* @param flip <code>true</code> if sensor input should be flipped, or <code>false</code> if not.
* @return this object so that methods can be chained; never null
*/
public TalonSRX reverseSensor(boolean flip);

/**
* Set the soft limit for forward motion, which will disable the motor when the sensor is out of range.
*
Expand Down Expand Up @@ -132,6 +203,16 @@ public interface TalonSRX extends LimitedMotor {
*/
public TalonSRX enableBrakeMode(boolean brake);

/**
* The Talon SRX can be set to honor a ramp rate to prevent instantaneous changes in throttle. This ramp rate is in effect
* regardless of which mode is selected (throttle, slave, or closed-loop). For example, setting the ramp rate to
* <code>6.0</code> will limit the maximum voltage change within any second to be less than or equal to 6.0 volts.
*
* @param rampRate maximum change in voltage per second, in volts / second
* @return this object so that methods can be chained; never null
*/
public TalonSRX setVoltageRampRate(double rampRate);

/**
* Get the faults currently associated with the Talon controller. These state of these faults may change at any time based
* upon the state of the module, and so they cannot be manually cleared.
Expand Down Expand Up @@ -209,6 +290,72 @@ public interface TalonSRX extends LimitedMotor {
*/
public boolean isAlive();

/**
* The type of feedback sensor used by this Talon controller.
*/
public enum FeedbackDevice {
/**
* Use Quadrature Encoder.
*/
QUADRATURE_ENCODER(0), /**
* Analog potentiometer, 0-3.3V
*/
ANALOG_POTENTIOMETER(2), /**
* Analog encoder or any other analog device, 0-3.3V
*/
ANALOG_ENCODER(3), /**
* Encoder that increments position per rising edge (and never decrements) on Quadrature-A.
*/
ENCODER_RISING(4), /**
* Encoder that increments position per falling edge (and never decrements) on Quadrature-A.
*/
ENCODER_FALLING(5);

public int value;

public static FeedbackDevice valueOf(int value) {
for (FeedbackDevice mode : values()) {
if (mode.value == value) {
return mode;
}
}
return null;
}

private FeedbackDevice(int value) {
this.value = value;
}

public int value() {
return this.value;
}
}

/**
* Types of status frame rates.
*/
public enum StatusFrameRate {
GENERAL(0), FEEDBACK(1), QUADRATURE_ENCODER(2), ANALOG_TEMPERATURE_BATTERY_VOLTAGE(3);
public int value;

public static StatusFrameRate valueOf(int value) {
for (StatusFrameRate mode : values()) {
if (mode.value == value) {
return mode;
}
}
return null;
}

private StatusFrameRate(int value) {
this.value = value;
}

public int value() {
return this.value;
}
}

/**
* The set of possible faults that this module can trigger.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -524,7 +524,7 @@ protected double currentFeedForward() {
return gains.feedForward;
}

protected final class Gains implements PIDController.Gains {
protected static final class Gains implements PIDController.Gains {
protected final double p;
protected final double i;
protected final double d;
Expand Down
Loading

0 comments on commit 4ee3a49

Please sign in to comment.