001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj.pidwrappers;
006
007import edu.wpi.first.wpilibj.DigitalSource;
008import edu.wpi.first.wpilibj.Encoder;
009import edu.wpi.first.wpilibj.PIDSource;
010import edu.wpi.first.wpilibj.PIDSourceType;
011
012/**
013 * Wrapper so that PIDSource is implemented for Encoder for old PIDController.
014 *
015 * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this
016 *     wrapper.
017 */
018@Deprecated(since = "2022", forRemoval = true)
019public class PIDEncoder extends Encoder implements PIDSource {
020  private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
021
022  public PIDEncoder(final int channelA, final int channelB, boolean reverseDirection) {
023    super(channelA, channelB, reverseDirection, EncodingType.k4X);
024  }
025
026  public PIDEncoder(final int channelA, final int channelB) {
027    super(channelA, channelB, false);
028  }
029
030  public PIDEncoder(
031      final int channelA,
032      final int channelB,
033      boolean reverseDirection,
034      final EncodingType encodingType) {
035    super(channelA, channelB, reverseDirection, encodingType);
036  }
037
038  public PIDEncoder(
039      final int channelA, final int channelB, final int indexChannel, boolean reverseDirection) {
040    super(channelA, channelB, indexChannel, reverseDirection);
041  }
042
043  public PIDEncoder(final int channelA, final int channelB, final int indexChannel) {
044    super(channelA, channelB, indexChannel, false);
045  }
046
047  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection) {
048    super(sourceA, sourceB, reverseDirection, EncodingType.k4X);
049  }
050
051  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB) {
052    super(sourceA, sourceB, false);
053  }
054
055  public PIDEncoder(
056      DigitalSource sourceA,
057      DigitalSource sourceB,
058      boolean reverseDirection,
059      final EncodingType encodingType) {
060    super(sourceA, sourceB, reverseDirection, encodingType);
061  }
062
063  public PIDEncoder(
064      DigitalSource sourceA,
065      DigitalSource sourceB,
066      DigitalSource indexSource,
067      boolean reverseDirection) {
068    super(sourceA, sourceB, indexSource, reverseDirection);
069  }
070
071  public PIDEncoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource) {
072    super(sourceA, sourceB, indexSource, false);
073  }
074
075  /**
076   * Set which parameter of the encoder you are using as a process control variable. The encoder
077   * class supports the rate and distance parameters.
078   *
079   * @param pidSource An enum to select the parameter.
080   */
081  @Override
082  public void setPIDSourceType(PIDSourceType pidSource) {
083    m_pidSource = pidSource;
084  }
085
086  @Override
087  public PIDSourceType getPIDSourceType() {
088    return m_pidSource;
089  }
090
091  /**
092   * Implement the PIDSource interface.
093   *
094   * @return The current value of the selected source parameter.
095   */
096  @Override
097  public double pidGet() {
098    switch (m_pidSource) {
099      case kDisplacement:
100        return getDistance();
101      case kRate:
102        return getRate();
103      default:
104        return 0.0;
105    }
106  }
107}