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.util.sendable.Sendable; 008import edu.wpi.first.util.sendable.SendableBuilder; 009import edu.wpi.first.util.sendable.SendableRegistry; 010import edu.wpi.first.wpilibj.MotorSafety; 011import edu.wpi.first.wpilibj.PWM; 012 013/** Common base class for all PWM Motor Controllers. */ 014public abstract class PWMMotorController extends MotorSafety 015 implements MotorController, Sendable, AutoCloseable { 016 private boolean m_isInverted; 017 protected PWM m_pwm; 018 019 /** 020 * Constructor. 021 * 022 * @param name Name to use for SendableRegistry 023 * @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are 024 * on the MXP port 025 */ 026 protected PWMMotorController(final String name, final int channel) { 027 m_pwm = new PWM(channel, false); 028 SendableRegistry.addLW(this, name, channel); 029 } 030 031 /** Free the resource associated with the PWM channel and set the value to 0. */ 032 @Override 033 public void close() { 034 SendableRegistry.remove(this); 035 m_pwm.close(); 036 } 037 038 /** 039 * Set the PWM value. 040 * 041 * <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the 042 * FPGA. 043 * 044 * @param speed The speed value between -1.0 and 1.0 to set. 045 */ 046 @Override 047 public void set(double speed) { 048 m_pwm.setSpeed(m_isInverted ? -speed : speed); 049 feed(); 050 } 051 052 /** 053 * Get the recently set value of the PWM. This value is affected by the inversion property. If you 054 * want the value that is sent directly to the MotorController, use {@link 055 * edu.wpi.first.wpilibj.PWM#getSpeed()} instead. 056 * 057 * @return The most recently set value for the PWM between -1.0 and 1.0. 058 */ 059 @Override 060 public double get() { 061 return m_pwm.getSpeed() * (m_isInverted ? -1.0 : 1.0); 062 } 063 064 @Override 065 public void setInverted(boolean isInverted) { 066 m_isInverted = isInverted; 067 } 068 069 @Override 070 public boolean getInverted() { 071 return m_isInverted; 072 } 073 074 @Override 075 public void disable() { 076 m_pwm.setDisabled(); 077 } 078 079 @Override 080 public void stopMotor() { 081 // Don't use set(0) as that will feed the watch kitty 082 m_pwm.setSpeed(0); 083 } 084 085 @Override 086 public String getDescription() { 087 return "PWM " + getChannel(); 088 } 089 090 /** 091 * Gets the backing PWM handle. 092 * 093 * @return The pwm handle. 094 */ 095 public int getPwmHandle() { 096 return m_pwm.getHandle(); 097 } 098 099 /** 100 * Gets the PWM channel number. 101 * 102 * @return The channel number. 103 */ 104 public int getChannel() { 105 return m_pwm.getChannel(); 106 } 107 108 /** 109 * Optionally eliminate the deadband from a motor controller. 110 * 111 * @param eliminateDeadband If true, set the motor curve for the motor controller to eliminate the 112 * deadband in the middle of the range. Otherwise, keep the full range without modifying any 113 * values. 114 */ 115 public void enableDeadbandElimination(boolean eliminateDeadband) { 116 m_pwm.enableDeadbandElimination(eliminateDeadband); 117 } 118 119 @Override 120 public void initSendable(SendableBuilder builder) { 121 builder.setSmartDashboardType("Motor Controller"); 122 builder.setActuator(true); 123 builder.setSafeState(this::disable); 124 builder.addDoubleProperty("Value", this::get, this::set); 125 } 126}