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 org.wpilib.hardware.motor;
006
007import static org.wpilib.units.Units.Volts;
008
009import org.wpilib.system.RobotController;
010import org.wpilib.units.measure.Voltage;
011
012/** Interface for motor controlling devices. */
013public interface MotorController {
014  /**
015   * Sets the duty cycle of the motor controller.
016   *
017   * @param dutyCycle The duty cycle between -1 and 1 (sign indicates direction).
018   */
019  void setDutyCycle(double dutyCycle);
020
021  /**
022   * Sets the voltage output of the motor controller.
023   *
024   * <p>Compensates for the current bus voltage to ensure that the desired voltage is output even if
025   * the battery voltage is below 12V - highly useful when the voltage outputs are "meaningful"
026   * (e.g. they come from a feedforward calculation).
027   *
028   * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
029   * properly - unlike the ordinary set function, it is not "set it and forget it."
030   *
031   * @param voltage The voltage.
032   */
033  default void setVoltage(double voltage) {
034    setDutyCycle(voltage / RobotController.getBatteryVoltage());
035  }
036
037  /**
038   * Sets the voltage output of the motor controller.
039   *
040   * <p>Compensates for the current bus voltage to ensure that the desired voltage is output even if
041   * the battery voltage is below 12V - highly useful when the voltage outputs are "meaningful"
042   * (e.g. they come from a feedforward calculation).
043   *
044   * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
045   * properly - unlike the ordinary set function, it is not "set it and forget it."
046   *
047   * @param voltage The voltage.
048   */
049  default void setVoltage(Voltage voltage) {
050    setVoltage(voltage.in(Volts));
051  }
052
053  /**
054   * Gets the duty cycle of the motor controller.
055   *
056   * @return The duty cycle between -1 and 1 (sign indicates direction).
057   */
058  double getDutyCycle();
059
060  /**
061   * Sets the inversion state of the motor controller.
062   *
063   * @param isInverted The inversion state.
064   */
065  void setInverted(boolean isInverted);
066
067  /**
068   * Gets the inversion state of the motor controller.
069   *
070   * @return The inversion state.
071   */
072  boolean getInverted();
073
074  /** Disables the motor controller. */
075  void disable();
076}