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 java.util.ArrayList; 008import org.wpilib.hardware.discrete.PWM; 009import org.wpilib.hardware.hal.SimDevice; 010import org.wpilib.hardware.hal.SimDevice.Direction; 011import org.wpilib.hardware.hal.SimDouble; 012import org.wpilib.system.RobotController; 013import org.wpilib.util.sendable.Sendable; 014import org.wpilib.util.sendable.SendableBuilder; 015import org.wpilib.util.sendable.SendableRegistry; 016 017/** Common base class for all PWM Motor Controllers. */ 018@SuppressWarnings("removal") 019public abstract class PWMMotorController extends MotorSafety 020 implements MotorController, Sendable, AutoCloseable { 021 private boolean m_isInverted; 022 private final ArrayList<PWMMotorController> m_followers = new ArrayList<>(); 023 024 /** PWM instances for motor controller. */ 025 protected PWM m_pwm; 026 027 private SimDevice m_simDevice; 028 private SimDouble m_simDutyCycle; 029 030 private boolean m_eliminateDeadband; 031 private int m_minPwm; 032 private int m_deadbandMinPwm; 033 private int m_centerPwm; 034 private int m_deadbandMaxPwm; 035 private int m_maxPwm; 036 037 /** 038 * Constructor. 039 * 040 * @param name Name to use for SendableRegistry 041 * @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are 042 * on the MXP port 043 */ 044 @SuppressWarnings("this-escape") 045 protected PWMMotorController(final String name, final int channel) { 046 m_pwm = new PWM(channel, false); 047 SendableRegistry.add(this, name, channel); 048 049 m_simDevice = SimDevice.create("PWMMotorController", channel); 050 if (m_simDevice != null) { 051 m_simDutyCycle = m_simDevice.createDouble("DutyCycle", Direction.kOutput, 0.0); 052 m_pwm.setSimDevice(m_simDevice); 053 } 054 } 055 056 /** Free the resource associated with the PWM channel and set the value to 0. */ 057 @Override 058 public void close() { 059 SendableRegistry.remove(this); 060 m_pwm.close(); 061 062 if (m_simDevice != null) { 063 m_simDevice.close(); 064 m_simDevice = null; 065 m_simDutyCycle = null; 066 } 067 } 068 069 private int getMinPositivePwm() { 070 if (m_eliminateDeadband) { 071 return m_deadbandMaxPwm; 072 } else { 073 return m_centerPwm + 1; 074 } 075 } 076 077 private int getMaxNegativePwm() { 078 if (m_eliminateDeadband) { 079 return m_deadbandMinPwm; 080 } else { 081 return m_centerPwm - 1; 082 } 083 } 084 085 private int getPositiveScaleFactor() { 086 return m_maxPwm - getMinPositivePwm(); 087 } 088 089 private int getNegativeScaleFactor() { 090 return getMaxNegativePwm() - m_minPwm; 091 } 092 093 /** 094 * Takes a duty cycle from -1 to 1 (the sign indicates direction), and outputs it in the 095 * microsecond format. 096 * 097 * @param dutyCycle The duty cycle between -1 and 1 (sign indicates direction). 098 */ 099 protected final void setDutyCycleInternal(double dutyCycle) { 100 if (Double.isFinite(dutyCycle)) { 101 dutyCycle = Math.clamp(dutyCycle, -1.0, 1.0); 102 } else { 103 dutyCycle = 0.0; 104 } 105 106 if (m_simDutyCycle != null) { 107 m_simDutyCycle.set(dutyCycle); 108 } 109 110 int rawValue; 111 if (dutyCycle == 0.0) { 112 rawValue = m_centerPwm; 113 } else if (dutyCycle > 0.0) { 114 rawValue = (int) Math.round(dutyCycle * getPositiveScaleFactor()) + getMinPositivePwm(); 115 } else { 116 rawValue = (int) Math.round(dutyCycle * getNegativeScaleFactor()) + getMaxNegativePwm(); 117 } 118 119 m_pwm.setPulseTimeMicroseconds(rawValue); 120 } 121 122 /** 123 * Gets the duty cycle from -1 to 1 (the sign indicates direction), from the currently set pulse 124 * time. 125 * 126 * @return motor controller duty cycle 127 */ 128 protected final double getDutyCycleInternal() { 129 int rawValue = m_pwm.getPulseTimeMicroseconds(); 130 131 if (rawValue == 0) { 132 return 0.0; 133 } else if (rawValue > m_maxPwm) { 134 return 1.0; 135 } else if (rawValue < m_minPwm) { 136 return -1.0; 137 } else if (rawValue > getMinPositivePwm()) { 138 return (rawValue - getMinPositivePwm()) / (double) getPositiveScaleFactor(); 139 } else if (rawValue < getMaxNegativePwm()) { 140 return (rawValue - getMaxNegativePwm()) / (double) getNegativeScaleFactor(); 141 } else { 142 return 0.0; 143 } 144 } 145 146 /** 147 * Sets the bounds in microseconds for the controller. 148 * 149 * @param maxPwm maximum 150 * @param deadbandMaxPwm deadband max 151 * @param centerPwm center 152 * @param deadbandMinPwm deadmand min 153 * @param minPwm minimum 154 */ 155 protected final void setBoundsMicroseconds( 156 int maxPwm, int deadbandMaxPwm, int centerPwm, int deadbandMinPwm, int minPwm) { 157 m_maxPwm = maxPwm; 158 m_deadbandMaxPwm = deadbandMaxPwm; 159 m_centerPwm = centerPwm; 160 m_deadbandMinPwm = deadbandMinPwm; 161 m_minPwm = minPwm; 162 } 163 164 @Override 165 public void setDutyCycle(double dutyCycle) { 166 if (m_isInverted) { 167 dutyCycle = -dutyCycle; 168 } 169 setDutyCycleInternal(dutyCycle); 170 171 for (var follower : m_followers) { 172 follower.setDutyCycle(dutyCycle); 173 } 174 175 feed(); 176 } 177 178 @Override 179 public double getDutyCycle() { 180 return getDutyCycleInternal() * (m_isInverted ? -1.0 : 1.0); 181 } 182 183 /** 184 * Gets the voltage output of the motor controller, nominally between -12 V and 12 V. 185 * 186 * @return The voltage of the motor controller, nominally between -12 V and 12 V. 187 */ 188 public double getVoltage() { 189 return getDutyCycle() * RobotController.getBatteryVoltage(); 190 } 191 192 @Override 193 public void setInverted(boolean isInverted) { 194 m_isInverted = isInverted; 195 } 196 197 @Override 198 public boolean getInverted() { 199 return m_isInverted; 200 } 201 202 @Override 203 public void disable() { 204 m_pwm.setDisabled(); 205 206 if (m_simDutyCycle != null) { 207 m_simDutyCycle.set(0.0); 208 } 209 210 for (var follower : m_followers) { 211 follower.disable(); 212 } 213 } 214 215 @Override 216 public void stopMotor() { 217 disable(); 218 } 219 220 @Override 221 public String getDescription() { 222 return "PWM " + getChannel(); 223 } 224 225 /** 226 * Gets the backing PWM handle. 227 * 228 * @return The pwm handle. 229 */ 230 public int getPwmHandle() { 231 return m_pwm.getHandle(); 232 } 233 234 /** 235 * Gets the PWM channel number. 236 * 237 * @return The channel number. 238 */ 239 public int getChannel() { 240 return m_pwm.getChannel(); 241 } 242 243 /** 244 * Optionally eliminate the deadband from a motor controller. 245 * 246 * @param eliminateDeadband If true, set the motor curve for the motor controller to eliminate the 247 * deadband in the middle of the range. Otherwise, keep the full range without modifying any 248 * values. 249 */ 250 public void enableDeadbandElimination(boolean eliminateDeadband) { 251 m_eliminateDeadband = eliminateDeadband; 252 } 253 254 /** 255 * Make the given PWM motor controller follow the output of this one. 256 * 257 * @param follower The motor controller follower. 258 */ 259 public void addFollower(PWMMotorController follower) { 260 m_followers.add(follower); 261 } 262 263 @Override 264 public void initSendable(SendableBuilder builder) { 265 builder.setSmartDashboardType("Motor Controller"); 266 builder.setActuator(true); 267 builder.addDoubleProperty("Value", this::getDutyCycle, this::setDutyCycle); 268 } 269}