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; 008import edu.wpi.first.wpilibj.SpeedController; 009 010/** Interface for motor controlling devices. */ 011@SuppressWarnings("removal") 012public interface MotorController extends SpeedController { 013 /** 014 * Common interface for setting the speed of a motor controller. 015 * 016 * @param speed The speed to set. Value should be between -1.0 and 1.0. 017 */ 018 @Override 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. 031 */ 032 @Override 033 default void setVoltage(double outputVolts) { 034 set(outputVolts / RobotController.getBatteryVoltage()); 035 } 036 037 /** 038 * Common interface for getting the current set speed of a motor controller. 039 * 040 * @return The current set speed. Value is between -1.0 and 1.0. 041 */ 042 @Override 043 double get(); 044 045 /** 046 * Common interface for inverting direction of a motor controller. 047 * 048 * @param isInverted The state of inversion true is inverted. 049 */ 050 @Override 051 void setInverted(boolean isInverted); 052 053 /** 054 * Common interface for returning if a motor controller is in the inverted state or not. 055 * 056 * @return isInverted The state of the inversion true is inverted. 057 */ 058 @Override 059 boolean getInverted(); 060 061 /** Disable the motor controller. */ 062 @Override 063 void disable(); 064 065 /** 066 * Stops motor movement. Motor can be moved again by calling set without having to re-enable the 067 * motor. 068 */ 069 @Override 070 void stopMotor(); 071}