projects
/
3501
/
stronghold-2016
/ commitdiff
commit
grep
author
committer
pickaxe
?
search:
re
summary
|
shortlog
|
log
|
commit
| commitdiff |
tree
raw
|
patch
|
inline
| side by side (parent:
ba29a57
)
More competition updates, intake speed and joystick scaling
author
Harel Dor
<hareldor@gmail.com>
Thu, 10 Mar 2016 06:03:31 +0000
(22:03 -0800)
committer
Harel Dor
<hareldor@gmail.com>
Thu, 10 Mar 2016 06:03:31 +0000
(22:03 -0800)
src/org/usfirst/frc/team3501/robot/Constants.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/Robot.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/commands/driving/ToggleFront.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
patch
|
blob
|
blame
|
history
diff --git
a/src/org/usfirst/frc/team3501/robot/Constants.java
b/src/org/usfirst/frc/team3501/robot/Constants.java
index 3c27d4884bb6ad77b8342cc5605196b1e674559f..923914bcb25588b825357ddcae6b9992bbd8075a 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/Constants.java
+++ b/
src/org/usfirst/frc/team3501/robot/Constants.java
@@
-41,6
+41,9
@@
public class Constants {
public static final int ARCADE = 1;
public static final int DRIVE_TYPE = TANK;
public static final int ARCADE = 1;
public static final int DRIVE_TYPE = TANK;
+ // Limits changes in speed during joystick driving
+ public static final double kADJUST = 8;
+
// Drivetrain Motor related ports
public static final int DRIVE_FRONT_LEFT = 1;
public static final int DRIVE_REAR_LEFT = 2;
// Drivetrain Motor related ports
public static final int DRIVE_FRONT_LEFT = 1;
public static final int DRIVE_REAR_LEFT = 2;
@@
-103,7
+106,7
@@
public class Constants {
public static final int OUT = -1;
// for roller
public static final int OUT = -1;
// for roller
- public static final double INTAKE_SPEED = 0.
5
;
- public static final double OUTPUT_SPEED = -0.
5
;
+ public static final double INTAKE_SPEED = 0.
7
;
+ public static final double OUTPUT_SPEED = -0.
7
;
}
}
}
}
diff --git
a/src/org/usfirst/frc/team3501/robot/Robot.java
b/src/org/usfirst/frc/team3501/robot/Robot.java
index 8616cfa765dd39fe98e3f3eeb42c6f3534c45b13..35bf8a584ac24f3028998e3215d6d6bf788cdc82 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/Robot.java
+++ b/
src/org/usfirst/frc/team3501/robot/Robot.java
@@
-1,8
+1,6
@@
package org.usfirst.frc.team3501.robot;
import org.usfirst.frc.team3501.robot.commands.driving.SetHighGear;
package org.usfirst.frc.team3501.robot;
import org.usfirst.frc.team3501.robot.commands.driving.SetHighGear;
-import org.usfirst.frc.team3501.robot.commands.intakearm.MoveIntakeArm;
-import org.usfirst.frc.team3501.robot.commands.shooter.ResetCatapult;
import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
import org.usfirst.frc.team3501.robot.subsystems.IntakeArm;
import org.usfirst.frc.team3501.robot.subsystems.Shooter;
import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
import org.usfirst.frc.team3501.robot.subsystems.IntakeArm;
import org.usfirst.frc.team3501.robot.subsystems.Shooter;
@@
-37,8
+35,6
@@
public class Robot extends IterativeRobot {
@Override
public void teleopInit() {
Scheduler.getInstance().add(new SetHighGear());
@Override
public void teleopInit() {
Scheduler.getInstance().add(new SetHighGear());
- Scheduler.getInstance().add(new ResetCatapult());
- Scheduler.getInstance().add(new MoveIntakeArm(Constants.IntakeArm.EXTEND));
}
@Override
}
@Override
diff --git
a/src/org/usfirst/frc/team3501/robot/commands/driving/ToggleFront.java
b/src/org/usfirst/frc/team3501/robot/commands/driving/ToggleFront.java
index ee7cfc51841ce8f7892d1e008d34fcde2e7dbd46..4c3d34fcd3896d57aa9b5420d96f2baabd9e9fc8 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/driving/ToggleFront.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/driving/ToggleFront.java
@@
-16,7
+16,7
@@
public class ToggleFront extends Command {
// Called just before this Command runs the first time
@Override
protected void initialize() {
// Called just before this Command runs the first time
@Override
protected void initialize() {
- Robot.driveTrain.
switchGear
();
+ Robot.driveTrain.
toggleFlipped
();
}
// Called repeatedly when this Command is scheduled to run
}
// Called repeatedly when this Command is scheduled to run
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
index eeac4900e1b9a5f44b8ca2e1951012c9b3b55376..3d406d7cbe506b886f86ed305d052d93e4953b9f 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
@@
-195,8
+195,18
@@
public class DriveTrain extends PIDSubsystem {
int type = Constants.DriveTrain.DRIVE_TYPE;
double k = (isFlipped() ? -1 : 1);
if (type == Constants.DriveTrain.TANK) {
int type = Constants.DriveTrain.DRIVE_TYPE;
double k = (isFlipped() ? -1 : 1);
if (type == Constants.DriveTrain.TANK) {
+ double leftSpeed = (-frontLeft.get() + -rearLeft.get()) / 2;
+ double rightSpeed = (-frontRight.get() + -rearRight.get()) / 2;
+ left = ((Constants.DriveTrain.kADJUST - 1) * leftSpeed + left)
+ / Constants.DriveTrain.kADJUST;
+ right = ((Constants.DriveTrain.kADJUST - 1) * rightSpeed + right)
+ / Constants.DriveTrain.kADJUST;
robotDrive.tankDrive(-left * k, -right * k);
} else if (type == Constants.DriveTrain.ARCADE) {
robotDrive.tankDrive(-left * k, -right * k);
} else if (type == Constants.DriveTrain.ARCADE) {
+ double speed = (-frontLeft.get() + -rearLeft.get() + -frontRight.get() + -rearRight
+ .get()) / 2;
+ left = ((Constants.DriveTrain.kADJUST - 1) * speed + left)
+ / Constants.DriveTrain.kADJUST;
robotDrive.arcadeDrive(left * k, right);
}
}
robotDrive.arcadeDrive(left * k, right);
}
}