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