projects
/
3501
/
2017steamworks
/ commitdiff
commit
grep
author
committer
pickaxe
?
search:
re
summary
|
shortlog
|
log
|
commit
| commitdiff |
tree
raw
|
patch
|
inline
| side by side (parent:
e323798
)
edit pid and limit motor values
author
Cindy Zhang
<cindyzyx9@gmail.com>
Mon, 20 Feb 2017 19:01:30 +0000
(11:01 -0800)
committer
Cindy Zhang
<cindyzyx9@gmail.com>
Mon, 20 Feb 2017 19:02:30 +0000
(11:02 -0800)
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/subsystems/Intake.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
patch
|
blob
|
blame
|
history
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
index 0a68c4ca001b815fb5af282900fc44f6d8fb8646..32ec7b221ab237ef17747dfa46f47f8246ace31b 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
@@
-1,6
+1,7
@@
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
import com.ctre.CANTalon;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
import com.ctre.CANTalon;
@@
-13,12
+14,12
@@
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
- public static double driveP = 0.0
12
, driveI = 0.0011, driveD = -0.002;
+ public static double driveP = 0.0
06
, driveI = 0.0011, driveD = -0.002;
public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
public static double driveStraightGyroP = 0.01;
public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
public static double driveStraightGyroP = 0.01;
- public static final double WHEEL_DIAMETER =
6
; // inches
- public static final
int
ENCODER_PULSES_PER_REVOLUTION = 256;
+ public static final double WHEEL_DIAMETER =
4
; // inches
+ public static final
double
ENCODER_PULSES_PER_REVOLUTION = 256;
public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
/ ENCODER_PULSES_PER_REVOLUTION;
public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
/ ENCODER_PULSES_PER_REVOLUTION;
@@
-75,7
+76,10
@@
public class DriveTrain extends Subsystem {
}
// DRIVE METHODS
}
// DRIVE METHODS
- public void setMotorValues(final double left, final double right) {
+ public void setMotorValues(double left, double right) {
+ left = MathLib.restrictToRange(left, 0.0, 1.0);
+ right = MathLib.restrictToRange(right, 0.0, 1.0);
+
frontLeft.set(left);
rearLeft.set(left);
frontLeft.set(left);
rearLeft.set(left);
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/Intake.java
b/src/org/usfirst/frc/team3501/robot/subsystems/Intake.java
index efde6a33e85ea0ba30ed35e43de36b3acf835cce..ed47fa702a80446343a32362991cb40fa3e8e41a 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/Intake.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/Intake.java
@@
-1,6
+1,7
@@
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
import com.ctre.CANTalon;
import com.ctre.CANTalon;
@@
-44,6
+45,7
@@
public class Intake extends Subsystem {
* from -1 to 1
*/
private void setSpeed(double speed) {
* from -1 to 1
*/
private void setSpeed(double speed) {
+ speed = MathLib.restrictToRange(speed, -1.0, 1.0);
intakeWheel.set(speed);
}
intakeWheel.set(speed);
}
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
index b9ccb42dff3967cabcfd551a0d71bb7c1ca31ad9..7a11c2d74440abff3dea25a9c2e60adbaad0e4d4 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
@@
-1,6
+1,7
@@
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
import com.ctre.CANTalon;
import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
import com.ctre.CANTalon;
@@
-8,12
+9,12
@@
import com.ctre.CANTalon;
import edu.wpi.first.wpilibj.command.Subsystem;
public class Shooter extends Subsystem {
import edu.wpi.first.wpilibj.command.Subsystem;
public class Shooter extends Subsystem {
- public double wheelP = 0
, wheelI = 0, wheelD = -0
;
+ public double wheelP = 0
.0003, wheelI = 0, wheelD = -0.00004
;
private static Shooter shooter;
private static HallEffectSensor hallEffect;
private final CANTalon flyWheel1, flyWheel2, indexWheel;
private static Shooter shooter;
private static HallEffectSensor hallEffect;
private final CANTalon flyWheel1, flyWheel2, indexWheel;
- public static final double DEFAULT_INDEXING_SPEED = -
0.75
;
+ public static final double DEFAULT_INDEXING_SPEED = -
1.0
;
public static final double DEFAULT_SHOOTING_SPEED = 0.75;
public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
public static final double DEFAULT_SHOOTING_SPEED = 0.75;
public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
@@
-49,7
+50,8
@@
public class Shooter extends Subsystem {
* @param val
* motor value from -1 to 1(fastest forward)
*/
* @param val
* motor value from -1 to 1(fastest forward)
*/
- public void setFlyWheelMotorVal(final double val) {
+ public void setFlyWheelMotorVal(double val) {
+ val = MathLib.restrictToRange(val, 0.0, 1.0);
flyWheel1.set(val);
flyWheel2.set(val);
}
flyWheel1.set(val);
flyWheel2.set(val);
}
@@
-68,7
+70,8
@@
public class Shooter extends Subsystem {
* @param val
* motor value from -1 to 1(fastest forward)
*/
* @param val
* motor value from -1 to 1(fastest forward)
*/
- public void setIndexWheelMotorVal(final double val) {
+ public void setIndexWheelMotorVal(double val) {
+ val = MathLib.restrictToRange(val, -1.0, 1.0);
indexWheel.set(val);
}
indexWheel.set(val);
}