Skip to content
This repository has been archived by the owner on Jan 28, 2019. It is now read-only.

Commit

Permalink
New auto shooting code
Browse files Browse the repository at this point in the history
  • Loading branch information
VaneRaklan committed Mar 5, 2017
1 parent 8736c81 commit a17e764
Show file tree
Hide file tree
Showing 5 changed files with 103 additions and 6 deletions.
2 changes: 1 addition & 1 deletion FRC_Robot2.0/.classpath
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<classpathentry kind="var" path="networktables" sourcepath="networktables.sources"/>
<classpathentry kind="var" path="opencv" sourcepath="opencv.sources"/>
<classpathentry kind="var" path="cscore" sourcepath="cscore.sources"/>
<classpathentry kind="var" path="USERLIBS_DIR/TalonSRXLibJava.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/navx_frc.jar"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRLib.jar"/>
<classpathentry kind="output" path="bin"/>
</classpath>
14 changes: 9 additions & 5 deletions FRC_Robot2.0/src/org/usfirst/frc/team2557/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,11 @@ public class Robot extends IterativeRobot {
public static final Acceleration_sub accel = new Acceleration_sub();
public static final SmartDashboard_sub dashboard = new SmartDashboard_sub();
public static OI oi;



Command _baseline;
Command Main_auto;
// Command autonomousCommand;
// SendableChooser<Command> chooser = new SendableChooser<>();

Expand All @@ -62,6 +64,7 @@ public void robotInit() {
CameraServer.getInstance().startAutomaticCapture();

_baseline = new Autonomous_Baseline();
Main_auto = new Main_auto();

oi = new OI();
oi.init();
Expand Down Expand Up @@ -102,7 +105,8 @@ public void disabledPeriodic() {
public void autonomousInit() {
// autonomousCommand = chooser.getSelected();

_baseline.start();
//_baseline.start();
// Main_auto.start();

/*
* String autoSelected = SmartDashboard.getString("Auto Selector",
Expand All @@ -112,8 +116,8 @@ public void autonomousInit() {
*/

// schedule the autonomous command (example)
// if (autonomousCommand != null)
// autonomousCommand.start();
if (Main_auto != null)
Main_auto.start();
}

/**
Expand All @@ -130,8 +134,8 @@ public void teleopInit() {
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
// if (autonomousCommand != null)
// autonomousCommand.cancel();
if (Main_auto != null)
Main_auto.cancel();
}

/**
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
package org.usfirst.frc.team2557.robot.autonomous;

import org.usfirst.frc.team2557.robot.RobotMap;

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

/**
*
*/
public class Auto_Shooter2 extends TimedCommand {

public Auto_Shooter2(double timeout) {
super(timeout);
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);
}

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

// Called repeatedly when this Command is scheduled to run
protected void execute() {
RobotMap.Lshooter.set(-.675);
RobotMap.Rshooter.set(.675);
RobotMap.copterAgitator.set(1);
RobotMap.agitator.set(-.65);
RobotMap.intake.set(.65);
}

// Called once after isFinished returns true
protected void end() {
RobotMap.Lshooter.set(0);
RobotMap.Rshooter.set(0);
RobotMap.copterAgitator.set(0);
RobotMap.agitator.set(0);
RobotMap.intake.set(0);

}

// 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
@@ -0,0 +1,42 @@
package org.usfirst.frc.team2557.robot.autonomous;

import org.usfirst.frc.team2557.robot.RobotMap;

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

/**
*
*/
public class Autonomus_Shooter extends TimedCommand {



public Autonomus_Shooter(double timeout) {
super(timeout);
// Use requires() here to declare subsystem dependencies
// eg. requires(chassis);


}

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

}

// Called repeatedly when this Command is scheduled to run
protected void execute() {
RobotMap.Lshooter.set(-.675);
RobotMap.Rshooter.set(.675);
}

// 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 @@ -8,6 +8,11 @@
public class Main_auto extends CommandGroup {

public Main_auto() {

addSequential(new TimedDrive(1.4,false,.75));
addSequential(new TimedDrive(.5,true, .75));
addParallel(new Autonomus_Shooter(.5));
addSequential(new Auto_Shooter2(10));
// Add Commands here:
// e.g. addSequential(new Command1());
// addSequential(new Command2());
Expand Down

0 comments on commit a17e764

Please sign in to comment.