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.motorcontrol;
006
007import edu.wpi.first.hal.SimDevice;
008import edu.wpi.first.hal.SimDevice.Direction;
009import edu.wpi.first.hal.SimDouble;
010import edu.wpi.first.util.sendable.Sendable;
011import edu.wpi.first.util.sendable.SendableBuilder;
012import edu.wpi.first.util.sendable.SendableRegistry;
013import edu.wpi.first.wpilibj.MotorSafety;
014import edu.wpi.first.wpilibj.PWM;
015import edu.wpi.first.wpilibj.RobotController;
016import java.util.ArrayList;
017
018/** Common base class for all PWM Motor Controllers. */
019@SuppressWarnings("removal")
020public abstract class PWMMotorController extends MotorSafety
021    implements MotorController, Sendable, AutoCloseable {
022  private boolean m_isInverted;
023  private final ArrayList<PWMMotorController> m_followers = new ArrayList<>();
024
025  /** PWM instances for motor controller. */
026  protected PWM m_pwm;
027
028  private SimDevice m_simDevice;
029  private SimDouble m_simSpeed;
030
031  private boolean m_eliminateDeadband;
032  private int m_minPwm;
033  private int m_deadbandMinPwm;
034  private int m_centerPwm;
035  private int m_deadbandMaxPwm;
036  private int m_maxPwm;
037
038  /**
039   * Constructor.
040   *
041   * @param name Name to use for SendableRegistry
042   * @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are
043   *     on the MXP port
044   */
045  @SuppressWarnings("this-escape")
046  protected PWMMotorController(final String name, final int channel) {
047    m_pwm = new PWM(channel, false);
048    SendableRegistry.add(this, name, channel);
049
050    m_simDevice = SimDevice.create("PWMMotorController", channel);
051    if (m_simDevice != null) {
052      m_simSpeed = m_simDevice.createDouble("Speed", Direction.kOutput, 0.0);
053      m_pwm.setSimDevice(m_simDevice);
054    }
055  }
056
057  /** Free the resource associated with the PWM channel and set the value to 0. */
058  @Override
059  public void close() {
060    SendableRegistry.remove(this);
061    m_pwm.close();
062
063    if (m_simDevice != null) {
064      m_simDevice.close();
065      m_simDevice = null;
066      m_simSpeed = null;
067    }
068  }
069
070  private int getMinPositivePwm() {
071    if (m_eliminateDeadband) {
072      return m_deadbandMaxPwm;
073    } else {
074      return m_centerPwm + 1;
075    }
076  }
077
078  private int getMaxNegativePwm() {
079    if (m_eliminateDeadband) {
080      return m_deadbandMinPwm;
081    } else {
082      return m_centerPwm - 1;
083    }
084  }
085
086  private int getPositiveScaleFactor() {
087    return m_maxPwm - getMinPositivePwm();
088  }
089
090  private int getNegativeScaleFactor() {
091    return getMaxNegativePwm() - m_minPwm;
092  }
093
094  /**
095   * Takes a speed from -1 to 1, and outputs it in the microsecond format.
096   *
097   * @param speed the speed to output
098   */
099  protected final void setSpeed(double speed) {
100    if (Double.isFinite(speed)) {
101      speed = Math.clamp(speed, -1.0, 1.0);
102    } else {
103      speed = 0.0;
104    }
105
106    if (m_simSpeed != null) {
107      m_simSpeed.set(speed);
108    }
109
110    int rawValue;
111    if (speed == 0.0) {
112      rawValue = m_centerPwm;
113    } else if (speed > 0.0) {
114      rawValue = (int) Math.round(speed * getPositiveScaleFactor()) + getMinPositivePwm();
115    } else {
116      rawValue = (int) Math.round(speed * getNegativeScaleFactor()) + getMaxNegativePwm();
117    }
118
119    m_pwm.setPulseTimeMicroseconds(rawValue);
120  }
121
122  /**
123   * Gets the speed from -1 to 1, from the currently set pulse time.
124   *
125   * @return motor controller speed
126   */
127  protected final double getSpeed() {
128    int rawValue = m_pwm.getPulseTimeMicroseconds();
129
130    if (rawValue == 0) {
131      return 0.0;
132    } else if (rawValue > m_maxPwm) {
133      return 1.0;
134    } else if (rawValue < m_minPwm) {
135      return -1.0;
136    } else if (rawValue > getMinPositivePwm()) {
137      return (rawValue - getMinPositivePwm()) / (double) getPositiveScaleFactor();
138    } else if (rawValue < getMaxNegativePwm()) {
139      return (rawValue - getMaxNegativePwm()) / (double) getNegativeScaleFactor();
140    } else {
141      return 0.0;
142    }
143  }
144
145  /**
146   * Sets the bounds in microseconds for the controller.
147   *
148   * @param maxPwm maximum
149   * @param deadbandMaxPwm deadband max
150   * @param centerPwm center
151   * @param deadbandMinPwm deadmand min
152   * @param minPwm minimum
153   */
154  protected final void setBoundsMicroseconds(
155      int maxPwm, int deadbandMaxPwm, int centerPwm, int deadbandMinPwm, int minPwm) {
156    m_maxPwm = maxPwm;
157    m_deadbandMaxPwm = deadbandMaxPwm;
158    m_centerPwm = centerPwm;
159    m_deadbandMinPwm = deadbandMinPwm;
160    m_minPwm = minPwm;
161  }
162
163  /**
164   * Set the PWM value.
165   *
166   * <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the
167   * FPGA.
168   *
169   * @param speed The speed value between -1.0 and 1.0 to set.
170   */
171  @Override
172  public void set(double speed) {
173    if (m_isInverted) {
174      speed = -speed;
175    }
176    setSpeed(speed);
177
178    for (var follower : m_followers) {
179      follower.set(speed);
180    }
181
182    feed();
183  }
184
185  /**
186   * Get the recently set value of the PWM. This value is affected by the inversion property.
187   *
188   * @return The most recently set value for the PWM between -1.0 and 1.0.
189   */
190  @Override
191  public double get() {
192    return getSpeed() * (m_isInverted ? -1.0 : 1.0);
193  }
194
195  /**
196   * Gets the voltage output of the motor controller, nominally between -12 V and 12 V.
197   *
198   * @return The voltage of the motor controller, nominally between -12 V and 12 V.
199   */
200  public double getVoltage() {
201    return get() * RobotController.getBatteryVoltage();
202  }
203
204  @Override
205  public void setInverted(boolean isInverted) {
206    m_isInverted = isInverted;
207  }
208
209  @Override
210  public boolean getInverted() {
211    return m_isInverted;
212  }
213
214  @Override
215  public void disable() {
216    m_pwm.setDisabled();
217
218    if (m_simSpeed != null) {
219      m_simSpeed.set(0.0);
220    }
221
222    for (var follower : m_followers) {
223      follower.disable();
224    }
225  }
226
227  @Override
228  public void stopMotor() {
229    // Don't use set(0) as that will feed the watch kitty
230    m_pwm.setPulseTimeMicroseconds(0);
231
232    for (var follower : m_followers) {
233      follower.stopMotor();
234    }
235  }
236
237  @Override
238  public String getDescription() {
239    return "PWM " + getChannel();
240  }
241
242  /**
243   * Gets the backing PWM handle.
244   *
245   * @return The pwm handle.
246   */
247  public int getPwmHandle() {
248    return m_pwm.getHandle();
249  }
250
251  /**
252   * Gets the PWM channel number.
253   *
254   * @return The channel number.
255   */
256  public int getChannel() {
257    return m_pwm.getChannel();
258  }
259
260  /**
261   * Optionally eliminate the deadband from a motor controller.
262   *
263   * @param eliminateDeadband If true, set the motor curve for the motor controller to eliminate the
264   *     deadband in the middle of the range. Otherwise, keep the full range without modifying any
265   *     values.
266   */
267  public void enableDeadbandElimination(boolean eliminateDeadband) {
268    m_eliminateDeadband = eliminateDeadband;
269  }
270
271  /**
272   * Make the given PWM motor controller follow the output of this one.
273   *
274   * @param follower The motor controller follower.
275   */
276  public void addFollower(PWMMotorController follower) {
277    m_followers.add(follower);
278  }
279
280  @Override
281  public void initSendable(SendableBuilder builder) {
282    builder.setSmartDashboardType("Motor Controller");
283    builder.setActuator(true);
284    builder.addDoubleProperty("Value", this::get, this::set);
285  }
286}