/** * Copyright (c) FIRST 2008-2012. All Rights Reserved. * Open Source Software - may be modified and shared by FRC teams. The code * must be accompanied by the FIRST BSD license file in the root directory of * the project. * * Copyright (c) 2011-2012, 2015-2016 Luke Shumaker * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions are met: * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright * notice, this list of conditions and the following disclaimer in the * documentation and/or other materials provided with the distribution. * * Neither the name of the FIRST nor the * names of its contributors may be used to endorse or promote products * derived from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * @author Luke Shumaker */ package org.usfirst.frc.team4272.robotlib; import edu.wpi.first.wpilibj.PIDOutput; import edu.wpi.first.wpilibj.PIDSource; import edu.wpi.first.wpilibj.SpeedController; //import edu.wpi.first.wpilibj.PIDController; /** * An enhanced variant of {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController} * (implements a PID Control Loop). *

* It is enhanced from * {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController} * in that it that also: *

*/ public class PIDController extends edu.wpi.first.wpilibj.PIDController implements SpeedController { private boolean NaNDisabled = false; private boolean inverted = false; public final PIDSource source; public final PIDOutput output; /** * Allocate a PID object with the given constants for P, I, D, and F *$ * @param Kp the proportional coefficient * @param Ki the integral coefficient * @param Kd the derivative coefficient * @param Kf the feed forward term * @param source The PIDSource object that is used to get values * @param output The PIDOutput object that is set to the output percentage * @param period the loop time for doing calculations. This particularly * effects calculations of the integral and differential terms. The * default is 50ms. */ public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output, double period) { super(Kp, Ki, Kd, Kf, source, output, period); this.source = source; this.output = output; } /* Convenience constructors *******************************************/ /* `Kf`, and `period` are optional */ /** * Convenience constructor with {@code Kf} defaulting to * {@code 0.0}. * * @param Kp the proportional coefficient * @param Ki the integral coefficient * @param Kd the derivative coefficient * @param source The PIDSource object that is used to get values * @param output The PIDOutput object that is set to the output percentage * @param period the loop time for doing calculations. This particularly * effects calculations of the integral and differential terms. The * default is 50ms. */ public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period) { this(Kp, Ki, Kd, 0.0, source, output, period); } /** * Convenience constructor with {@code period} defaulting to * {@link #kDefaultPeriod}. * * @param Kp the proportional coefficient * @param Ki the integral coefficient * @param Kd the derivative coefficient * @param Kf the feed forward term * @param source The PIDSource object that is used to get values * @param output The PIDOutput object that is set to the output percentage */ public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source, PIDOutput output) { this(Kp, Ki, Kd, Kf, source, output, kDefaultPeriod); } /** * Convenience constructor with {@code Kf} defaulting to * {@code 0.0}, and {@code period} defaulting to * {@link #kDefaultPeriod}. * * @param Kp the proportional coefficient * @param Ki the integral coefficient * @param Kd the derivative coefficient * @param source The PIDSource object that is used to get values * @param output The PIDOutput object that is set to the output percentage */ public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) { this(Kp, Ki, Kd, 0.0, source, output, kDefaultPeriod); } /* Override to auto-disable if setpoint is NaN, and invert ************/ /** * {@inheritDoc} */ @Override public synchronized void setSetpoint(double setpoint) { if (Double.isNaN(setpoint)) { NaNDisabled = true; super.disable(); } else { if (NaNDisabled && !isEnabled()) { enable(); } super.setSetpoint((inverted ? -1 : 1) * setpoint); } } /** * {@inheritDoc} */ @Override public synchronized void enable() { NaNDisabled = false; super.enable(); } /** * {@inheritDoc} */ @Override public synchronized void disable() { NaNDisabled = false; super.disable(); } /* Implement PIDOutput (a parent of SpeedController) *******************/ /** * {@inheritDoc} */ @Override public void pidWrite(double output) { setSetpoint(output); } /* Implement SpeedController *******************************************/ /** * {@inheritDoc} */ @Override public void set(double output) { setSetpoint(output); } /** * Don't use this. * @deprecated Don't use this; it is leaking up from * {@link edu.wpi.first.wpilibj.CANJaguar} through * {@link edu.wpi.first.wpilibj.SpeedController} */ @Override public void set(double output, byte syncGroup) { set(output); } /** * {@inheritDoc} */ @Override public void setInverted(boolean isInverted) { inverted = isInverted; } /** * {@inheritDoc} */ @Override public boolean getInverted() { return inverted; } }