~shadow-h511/robototes2412java/mecanum

« back to all changes in this revision

Viewing changes to src/com/shadowh511/mayor/Tomo.java

  • Committer: shadowh511
  • Date: 2010-04-03 01:33:25 UTC
  • Revision ID: shadow.h511@gmail.com-20100403013325-5qde3om3b7v5fuae
Wow, i havent commited in a long time.  There are a LOT of changes this time around, its all object-oriented, and it uses threads.

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
package com.shadowh511.mayor;
 
2
 
 
3
/*
 
4
 * For use with a barebones robot.  It has two motors and two jags 1 and 2
 
5
 * respectively.  It also has a switch to get input for a sensor so it can
 
6
 * automatically kick balls, if it had such a mechanism;
 
7
 */
 
8
 
 
9
import edu.wpi.first.wpilibj.SimpleRobot;
 
10
import edu.wpi.first.wpilibj.Timer;
 
11
import com.shadowh511.mayor.inputs.Attack3;
 
12
import com.shadowh511.mayor.inputs.Switch;
 
13
import com.shadowh511.mayor.outputs.Driver;
 
14
import com.shadowh511.mayor.outputs.ConstantMotorThread;
 
15
import com.shadowh511.mayor.outputs.Firing;
 
16
import com.shadowh511.mayor.outputs.FiringThread;
 
17
import com.shadowh511.mayor.utils.EasyDriverStationLCD;
 
18
 
 
19
public class Tomo extends SimpleRobot {
 
20
    Attack3 driver_L = new Attack3(1);
 
21
    Attack3 driver_R = new Attack3(2);
 
22
    Driver motors = new Driver(1,2);
 
23
    EasyDriverStationLCD lcd = new EasyDriverStationLCD();
 
24
    Switch balls = new Switch(4);
 
25
    ConstantMotorThread magnet;
 
26
    //Firing gun = new Firing();
 
27
    FiringThread gun = new FiringThread();
 
28
    private static Tomo instance; //The ConstantMotorThread gets data from the main Robot class, among other things
 
29
 
 
30
    long loops;
 
31
 
 
32
    public void robotInit() {
 
33
        magnet = new ConstantMotorThread(7);
 
34
        magnet.start();
 
35
        System.out.println("ConstantMotor thread started");
 
36
        getWatchdog().setEnabled(false);
 
37
        getWatchdog().kill();
 
38
    }
 
39
 
 
40
    /**
 
41
     * This function is called once each time the robot enters autonomous mode.
 
42
     */
 
43
    public void autonomous() {
 
44
        this.robotInit();
 
45
        getWatchdog().setEnabled(false);
 
46
        getWatchdog().kill();
 
47
 
 
48
        System.out.println("Autonomous Enabled");
 
49
 
 
50
        lcd.clear();
 
51
        lcd.writeOnLine(0, "AUTONOMOUS", 0);
 
52
        lcd.draw();
 
53
 
 
54
        motors.drive(0.5);  //Drives in a square, hopefully
 
55
        Timer.delay(0.5);
 
56
        motors.tankDrive(0.5, -0.5);
 
57
        Timer.delay(0.25);
 
58
        motors.drive(0.5);
 
59
        Timer.delay(0.5);
 
60
        motors.tankDrive(0.5, -0.5);
 
61
        Timer.delay(0.25);
 
62
        motors.drive(0.5);
 
63
        Timer.delay(0.5);
 
64
        motors.tankDrive(0.5, -0.5);
 
65
        Timer.delay(0.25);
 
66
        motors.drive(0.5);
 
67
        Timer.delay(0.5);
 
68
        motors.tankDrive(0.5, -0.5);
 
69
        Timer.delay(0.25);
 
70
 
 
71
        System.out.println("Automous Disabled");
 
72
    }
 
73
 
 
74
    /**
 
75
     * This function is called once each time the robot enters operator control.
 
76
     */
 
77
    public void operatorControl() {
 
78
        this.robotInit();
 
79
        getWatchdog().setEnabled(false);
 
80
        getWatchdog().kill();
 
81
 
 
82
        lcd.clear();
 
83
        lcd.writeOnLine(0, "TELEOPERATED", 0);
 
84
        lcd.draw();
 
85
 
 
86
        loops = 0;
 
87
 
 
88
        System.out.println("Teleop Enabled");
 
89
        
 
90
        while(isEnabled()) {
 
91
            lcd.writeOnLine(1, ""+loops, 0);
 
92
 
 
93
            motors.tankDrive(driver_L, driver_R);
 
94
            loops ++;
 
95
 
 
96
            if(balls.get()) {
 
97
                lcd.writeOnLine(2, "TRUE ", 0);
 
98
            } else {
 
99
                lcd.writeOnLine(2, "FALSE", 0);
 
100
            }
 
101
            
 
102
            lcd.draw();
 
103
        }
 
104
 
 
105
        System.out.println("Teleop Disabled");
 
106
    }
 
107
 
 
108
    public static Tomo getInstance() { //For other threads to use robot states
 
109
        return instance;
 
110
    }
 
111
}