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.pidwrappers; 006 007import edu.wpi.first.util.sendable.Sendable; 008import edu.wpi.first.util.sendable.SendableBuilder; 009import edu.wpi.first.wpilibj.PIDOutput; 010import edu.wpi.first.wpilibj.motorcontrol.MotorController; 011 012/** 013 * Wrapper so that PIDOutput is implemented for MotorController for old PIDController. 014 * 015 * @deprecated Use {@link edu.wpi.first.math.controller.PIDController} which doesn't require this 016 * wrapper. 017 */ 018@Deprecated(since = "2022", forRemoval = true) 019public class PIDMotorController implements PIDOutput, MotorController, Sendable { 020 private final MotorController m_motorController; 021 022 public PIDMotorController(MotorController motorController) { 023 m_motorController = motorController; 024 } 025 026 /** 027 * Write out the PID value as seen in the PIDOutput base object. 028 * 029 * @param output Write out the PWM value as was found in the PIDController 030 */ 031 @Override 032 public void pidWrite(double output) { 033 m_motorController.set(output); 034 } 035 036 /** 037 * Common interface for setting the speed of a motor controller. 038 * 039 * @param speed The speed to set. Value should be between -1.0 and 1.0. 040 */ 041 @Override 042 public void set(double speed) { 043 m_motorController.set(speed); 044 } 045 046 /** 047 * Sets the voltage output of the MotorController. Compensates for the current bus voltage to 048 * ensure that the desired voltage is output even if the battery voltage is below 12V - highly 049 * useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward 050 * calculation). 051 * 052 * <p>NOTE: This function *must* be called regularly in order for voltage compensation to work 053 * properly - unlike the ordinary set function, it is not "set it and forget it." 054 * 055 * @param outputVolts The voltage to output. 056 */ 057 @Override 058 public void setVoltage(double outputVolts) { 059 m_motorController.setVoltage(outputVolts); 060 } 061 062 /** 063 * Common interface for getting the current set speed of a motor controller. 064 * 065 * @return The current set speed. Value is between -1.0 and 1.0. 066 */ 067 @Override 068 public double get() { 069 return m_motorController.get(); 070 } 071 072 /** 073 * Common interface for inverting direction of a motor controller. 074 * 075 * @param isInverted The state of inversion true is inverted. 076 */ 077 @Override 078 public void setInverted(boolean isInverted) { 079 m_motorController.setInverted(isInverted); 080 } 081 082 /** 083 * Common interface for returning if a motor controller is in the inverted state or not. 084 * 085 * @return isInverted The state of the inversion true is inverted. 086 */ 087 @Override 088 public boolean getInverted() { 089 return m_motorController.getInverted(); 090 } 091 092 /** Disable the motor controller. */ 093 @Override 094 public void disable() { 095 m_motorController.disable(); 096 } 097 098 /** 099 * Stops motor movement. Motor can be moved again by calling set without having to re-enable the 100 * motor. 101 */ 102 @Override 103 public void stopMotor() { 104 m_motorController.stopMotor(); 105 } 106 107 @Override 108 public void initSendable(SendableBuilder builder) { 109 builder.setSmartDashboardType("Motor Controller"); 110 builder.setActuator(true); 111 builder.setSafeState(this::disable); 112 builder.addDoubleProperty("Value", this::get, this::set); 113 } 114}