Skip to content

Commit

Permalink
Added comments. Added tunable steer compensation to autonomous
Browse files Browse the repository at this point in the history
  • Loading branch information
briansemrau committed Feb 28, 2018
1 parent 51d4ccf commit c52fe34
Show file tree
Hide file tree
Showing 14 changed files with 222 additions and 151 deletions.
4 changes: 3 additions & 1 deletion src/org/usfirst/frc/team4737/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ public class Robot extends TimedRobot {
public static final Intake INTAKE = new Intake();
public static final Climber CLIMBER = new Climber();
public static final ControlSystem CONTROLSYSTEM = new ControlSystem();

public static final OI OI = new OI(); // Must initialize after subsystems

private Command autonomousCommand;
Expand All @@ -45,6 +45,7 @@ public class Robot extends TimedRobot {
public void robotInit() {
chooser.addDefault("No Auto", null);
chooser.addObject("Blind Baseline", new AutoBlindBaseline());
// Add new autonomous routines here
SmartDashboard.putData("Auto mode", chooser);
}

Expand All @@ -55,6 +56,7 @@ public void robotInit() {
*/
@Override
public void disabledInit() {
// Puts robot into coast mode, allowing it to be pushed more easily
new RelaxDrivetrain().start();
}

Expand Down
33 changes: 29 additions & 4 deletions src/org/usfirst/frc/team4737/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,39 @@ public class RobotMap {
/**
* The voltage to give to the elevator for it to hold constant position with a
* cube
*
* Increase this value if the elevator droops too much while holding the cube
*/
public static final double ELEVATOR_HOLD_V = 1;
/**
* The number of seconds to keep the elevator in place before letting the motor
* relax. To disable this, set the value to 0.1
*/
public static final double ELEVATOR_HOLD_V = 1; // TODO measure
public static final double ELEVATOR_HOLD_TIME = 4; // TODO tune
public static final double ELEVATOR_MAX_DOWN_SPEED = -0.6; // TODO tune

/**
* The maximum speed the elevator is allowed to go down. This prevents
* unspooling too quickly, which causes the rope to fall off the spool.
*/
public static final double ELEVATOR_MAX_DOWN_SPEED = -0.6;

/**
* The value to multiply the throttle by when slow driving is enabled
*/
public static final double DRIVE_SLOW_SCALE = 0.5;


/*
* Adjust these variables to tune autonomous
*/
public static final double AUTO_BLIND_TIME = 5;
public static final double AUTO_BLIND_SPEED = 0.3;
/**
* The steering value to use in autonomous to counteract any natural tendencies
* for the robot to veer left or right. A positive value (should) steer the
* robot to the right, and negative to the left.
*
* Tune this value accordingly. It may need to be adjusted throughout the
* competition.
*/
public static final double AUTO_BLIND_STEER = 0;

}
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,5 @@ protected void end() {
// subsystems is scheduled to run
protected void interrupted() {
}

}
Original file line number Diff line number Diff line change
@@ -1,69 +1,88 @@
package org.usfirst.frc.team4737.robot.commands.drivetrain;

import org.usfirst.frc.team4737.robot.Robot;
import org.usfirst.frc.team4737.robot.RobotMap;

import edu.wpi.first.wpilibj.command.Command;

/**
*
* Autonomously accelerates/decelerates the robot to a target speed from a
* starting speed.
*/
public class AutoBlindAccelerate extends Command {

private double percentPerSecond;
private double startPercent;
private double targetPercent;

private boolean startLow;

private double lastTime;
private double percent;

public AutoBlindAccelerate(double percentPerSecond, double startPercent, double targetPercent) {
requires(Robot.DRIVETRAIN);
this.percentPerSecond = percentPerSecond;
this.startPercent = startPercent;
this.targetPercent = targetPercent;
}

// Called just before this Command runs the first time
protected void initialize() {
lastTime = 0;
percent = startPercent;
startLow = startPercent < targetPercent;
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
double time = this.timeSinceInitialized();
double delta = time - lastTime;
lastTime = time;

// Adjust speed
if (startLow) percent += percentPerSecond * delta;
else percent -= percentPerSecond * delta;

// Check bounds
if (startLow && percent > targetPercent) percent = targetPercent;
if (!startLow && percent < targetPercent) percent = targetPercent;
if (percent < -1) percent = -1;
if (percent > 1) percent = 1;

// Apply speed
Robot.DRIVETRAIN.arcadeDrive(percent, 0);
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return percent == targetPercent;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}


/**
*
* @param percentPerSecond
* The % speed to accelerate by per second. A value of 1 will
* accelerate the robot from a standstill to full speed in one
* second.
* @param startPercent
* The initial speed (between -1.0 and 1.0) of the robot.
* @param targetPercent
* The speed (between -1.0 and 1.0) to accelerate to.
*/
public AutoBlindAccelerate(double percentPerSecond, double startPercent, double targetPercent) {
requires(Robot.DRIVETRAIN);
this.percentPerSecond = percentPerSecond;
this.startPercent = startPercent;
this.targetPercent = targetPercent;
}

// Called just before this Command runs the first time
protected void initialize() {
lastTime = 0;
percent = startPercent;
startLow = startPercent < targetPercent;
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
double time = this.timeSinceInitialized();
double delta = time - lastTime;
lastTime = time;

// Adjust speed based on time passed
if (startLow)
percent += percentPerSecond * delta;
else
percent -= percentPerSecond * delta;

// Check bounds
if (startLow && percent > targetPercent)
percent = targetPercent;
if (!startLow && percent < targetPercent)
percent = targetPercent;
if (percent < -1)
percent = -1;
if (percent > 1)
percent = 1;

// Set drive speed
Robot.DRIVETRAIN.arcadeDrive(percent, RobotMap.AUTO_BLIND_STEER);
}

// Make this return true when this Command no longer needs to run execute()
protected boolean isFinished() {
return percent == targetPercent;
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -9,27 +9,39 @@
*/
public class AutoBlindBaseline extends CommandGroup {

public AutoBlindBaseline() {
// Add Commands here:
// e.g. addSequential(new Command1());
// addSequential(new Command2());
// these will run in order.

// To run multiple commands at the same time,
// use addParallel()
// e.g. addParallel(new Command1());
// addSequential(new Command2());
// Command1 and Command2 will run in parallel.

// A command group will require all of the subsystems that each member
// would require.
// e.g. if Command1 requires chassis, and Command2 requires arm,
// a CommandGroup containing them would require both the chassis and the
// arm.

addSequential(new AutoBlindAccelerate(0.1, 0, RobotMap.AUTO_BLIND_SPEED));
addSequential(new AutoBlindDrive(RobotMap.AUTO_BLIND_TIME, RobotMap.AUTO_BLIND_SPEED));
addSequential(new AutoBlindAccelerate(0.1, RobotMap.AUTO_BLIND_SPEED, 0));
}

public AutoBlindBaseline() {
// Add Commands here:
// e.g. addSequential(new Command1());
// addSequential(new Command2());
// these will run in order.

// To run multiple commands at the same time,
// use addParallel()
// e.g. addParallel(new Command1());
// addSequential(new Command2());
// Command1 and Command2 will run in parallel.

// A command group will require all of the subsystems that each member
// would require.
// e.g. if Command1 requires chassis, and Command2 requires arm,
// a CommandGroup containing them would require both the chassis and the
// arm.

/*
* Accelerates the robot to the configured speed, drives for the configured
* time, and decelerates to a stop.
*
* If the robot drives too far, decrease the time. If the robot drives too fast,
* decrease the speed. If the robot speeds up too fast, decrease the
* acceleration. Likewise, if it takes too long to speed up, increase
* acceleration.
*
* If the robot veers left or right, adjust the AUTO_BLIND_STEER value in RobotMap.
*/
double acceleration = 0.1;
addSequential(new AutoBlindAccelerate(acceleration, 0, RobotMap.AUTO_BLIND_SPEED));
addSequential(new AutoBlindDrive(RobotMap.AUTO_BLIND_TIME, RobotMap.AUTO_BLIND_SPEED));
addSequential(new AutoBlindAccelerate(acceleration, RobotMap.AUTO_BLIND_SPEED, 0));
}

}
Original file line number Diff line number Diff line change
@@ -1,39 +1,51 @@
package org.usfirst.frc.team4737.robot.commands.drivetrain;

import org.usfirst.frc.team4737.robot.Robot;
import org.usfirst.frc.team4737.robot.RobotMap;

import edu.wpi.first.wpilibj.command.TimedCommand;

/**
*
* Drives the robot forward autonomously without sensor input. Drives at a
* certain speed for a certain time.
*
* This should be used only in conjunction with AutoBlindAccelerate to get up to
* speed. If the robot does not accelerate first, it may jerk and tip over.
*/
public class AutoBlindDrive extends TimedCommand {

private double percent;

public AutoBlindDrive(double time, double percent) {
super(time);
requires(Robot.DRIVETRAIN);

this.percent = percent;
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.DRIVETRAIN.arcadeDrive(percent, 0);
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}


/**
*
* @param time
* The number of seconds to drive forward for.
* @param percent
* The percent output, or speed (between -1.0 and 1.0) to drive at.
*/
public AutoBlindDrive(double time, double percent) {
super(time);
requires(Robot.DRIVETRAIN);

this.percent = percent;
}

// Called just before this Command runs the first time
protected void initialize() {
}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
Robot.DRIVETRAIN.arcadeDrive(percent, RobotMap.AUTO_BLIND_STEER);
}

// Called once after isFinished returns true
protected void end() {
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
protected void interrupted() {
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@
import edu.wpi.first.wpilibj.command.InstantCommand;

/**
*
* Configures the drivetrain to coast mode. This allows the robot to be pushed
* around more easily.
*/
public class RelaxDrivetrain extends InstantCommand {

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,10 @@ protected void initialize() {
// Called repeatedly when this Command is scheduled to run
protected void execute() {
// Control elevator movement, holding it in place by default

// Grab input
double input = Robot.OI.operator.getAxis("LS_Y").get();

// Check if we're hitting the top
// if (input > 0 && Robot.ELEVATOR.isAtTop()) {
// input = 0;
// }

// Make sure we don't go down too fast
if (input < RobotMap.ELEVATOR_MAX_DOWN_SPEED) {
input = RobotMap.ELEVATOR_MAX_DOWN_SPEED;
Expand All @@ -45,7 +42,6 @@ protected void execute() {

// Set elevator speed
Robot.ELEVATOR.setSpeed(input);

}

// Make this return true when this Command no longer needs to run execute()
Expand Down
Loading

0 comments on commit c52fe34

Please sign in to comment.