summaryrefslogtreecommitdiff
path: root/src/org/mckenzierobotics/lib/robot/FeedForward.java
blob: a275366fdac39e0ac7872a4074ddf37b25e9f98e (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
/**
 * Copyright (c) 2012 Precise Path Robotics, Inc
 *
 * This program is free software: you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation, either version 3 of the License, or
 * (at your option) any later version.
 * 
 * This program is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with this program.  If not, see <http://www.gnu.org/licenses/>.
 * 
 * @author Luke Shumaker <lukeshu@sbcglobal.net>
 */
package org.mckenzierobotics.lib.robot;

import edu.wpi.first.wpilibj.PIDOutput;
import edu.wpi.first.wpilibj.PIDSource;

/**
 *
 * @author Luke Shumaker <lukeshu@sbcglobal.net>
 */
public abstract class FeedForward implements PIDOutput {
	private class PIDTrigger implements PIDOutput {
		private FeedForward ff;
		public PIDTrigger(FeedForward ff) {
			this.ff = ff;
		}
		public void pidWrite(double output) {
			ff.update(output);
		}
	}
	private PIDController pid;
	private PIDOutput pidOutput;
	public FeedForward(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
		pidOutput = output;
		pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this));
	}
	public FeedForward(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period) {
		pidOutput = output;
		pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), period);
	}
	
	public FeedForward(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, boolean autodisable) {
		pidOutput = output;
		pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), autodisable);
	}
	public FeedForward(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period, boolean autodisable) {
		pidOutput = output;
		pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), period, autodisable);
	}
	
	public PIDController getPID() {
		return pid;
	}
	
	public void pidWrite(double output) {
		pid.setSetpoint(output);
	}
	
	public void update(double pidResult) {
		if (pid.isEnable()) {
			double ffResult = calculate(pid.getSetpoint());
			pidOutput.pidWrite(ffResult+pidResult);
		} else {
			pidOutput.pidWrite(0);
		}
	}
	
	public abstract double calculate(double setpoint);
}