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.wpilibj.RobotController;
008
009/** Interface for motor controlling devices. */
010public interface MotorController {
011  /**
012   * Common interface for setting the speed of a motor controller.
013   *
014   * @param speed The speed to set. Value should be between -1.0 and 1.0.
015   */
016  void set(double speed);
017
018  /**
019   * Sets the voltage output of the MotorController. Compensates for the current bus voltage to
020   * ensure that the desired voltage is output even if the battery voltage is below 12V - highly
021   * useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward
022   * calculation).
023   *
024   * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work
025   * properly - unlike the ordinary set function, it is not "set it and forget it."
026   *
027   * @param outputVolts The voltage to output.
028   */
029  default void setVoltage(double outputVolts) {
030    set(outputVolts / RobotController.getBatteryVoltage());
031  }
032
033  /**
034   * Common interface for getting the current set speed of a motor controller.
035   *
036   * @return The current set speed. Value is between -1.0 and 1.0.
037   */
038  double get();
039
040  /**
041   * Common interface for inverting direction of a motor controller.
042   *
043   * @param isInverted The state of inversion true is inverted.
044   */
045  void setInverted(boolean isInverted);
046
047  /**
048   * Common interface for returning if a motor controller is in the inverted state or not.
049   *
050   * @return isInverted The state of the inversion true is inverted.
051   */
052  boolean getInverted();
053
054  /** Disable the motor controller. */
055  void disable();
056
057  /**
058   * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
059   * motor.
060   */
061  void stopMotor();
062}